16 #ifndef NAV2_UTIL__ODOMETRY_UTILS_HPP_
17 #define NAV2_UTIL__ODOMETRY_UTILS_HPP_
26 #include "geometry_msgs/msg/twist.hpp"
27 #include "geometry_msgs/msg/twist_stamped.hpp"
28 #include "nav_msgs/msg/odometry.hpp"
29 #include "nav2_util/lifecycle_node.hpp"
30 #include "rclcpp/rclcpp.hpp"
31 #include "nav2_util/node_utils.hpp"
51 const rclcpp::Node::WeakPtr & parent,
52 double filter_duration = 0.3,
53 const std::string & odom_topic =
"odom");
63 const nav2_util::LifecycleNode::WeakPtr & parent,
64 double filter_duration = 0.3,
65 const std::string & odom_topic =
"odom");
73 std::lock_guard<std::mutex> lock(odom_mutex_);
74 if (!received_odom_) {
75 RCLCPP_ERROR(rclcpp::get_logger(
"OdomSmoother"),
76 "OdomSmoother has not received any data yet, returning empty Twist");
77 geometry_msgs::msg::Twist twist;
80 return vel_smooth_.twist;
89 std::lock_guard<std::mutex> lock(odom_mutex_);
90 if (!received_odom_) {
91 RCLCPP_ERROR(rclcpp::get_logger(
"OdomSmoother"),
92 "OdomSmoother has not received any data yet, returning empty Twist");
93 geometry_msgs::msg::TwistStamped twist_stamped;
105 std::lock_guard<std::mutex> lock(odom_mutex_);
106 if (!received_odom_) {
107 RCLCPP_ERROR(rclcpp::get_logger(
"OdomSmoother"),
108 "OdomSmoother has not received any data yet, returning empty Twist");
109 geometry_msgs::msg::Twist twist;
112 return odom_history_.back().twist.twist;
121 std::lock_guard<std::mutex> lock(odom_mutex_);
122 geometry_msgs::msg::TwistStamped twist_stamped;
123 if (!received_odom_) {
124 RCLCPP_ERROR(rclcpp::get_logger(
"OdomSmoother"),
125 "OdomSmoother has not received any data yet, returning empty Twist");
126 return twist_stamped;
128 twist_stamped.header = odom_history_.back().header;
129 twist_stamped.twist = odom_history_.back().twist.twist;
130 return twist_stamped;
138 void odomCallback(nav_msgs::msg::Odometry::SharedPtr msg);
146 rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
147 nav_msgs::msg::Odometry odom_cumulate_;
148 geometry_msgs::msg::TwistStamped vel_smooth_;
149 std::mutex odom_mutex_;
151 rclcpp::Duration odom_history_duration_;
152 std::deque<nav_msgs::msg::Odometry> odom_history_;
OdomSmoother(const rclcpp::Node::WeakPtr &parent, double filter_duration=0.3, const std::string &odom_topic="odom")
Constructor that subscribes to an Odometry topic.
void odomCallback(nav_msgs::msg::Odometry::SharedPtr msg)
Callback of odometry subscriber to process.
void updateState()
Update internal state of the smoother after getting new data.
geometry_msgs::msg::TwistStamped getRawTwistStamped()
Get raw twist stamped msg from smoother (without smoothing)
geometry_msgs::msg::Twist getRawTwist()
Get raw twist msg from smoother (without smoothing)
geometry_msgs::msg::Twist getTwist()
Get twist msg from smoother.
geometry_msgs::msg::TwistStamped getTwistStamped()
Get twist stamped msg from smoother.