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");
71 inline geometry_msgs::msg::Twist
getTwist() {
return vel_smooth_.twist;}
84 void odomCallback(nav_msgs::msg::Odometry::SharedPtr msg);
91 rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
92 nav_msgs::msg::Odometry odom_cumulate_;
93 geometry_msgs::msg::TwistStamped vel_smooth_;
94 std::mutex odom_mutex_;
96 rclcpp::Duration odom_history_duration_;
97 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::Twist getTwist()
Get twist msg from smoother.
geometry_msgs::msg::TwistStamped getTwistStamped()
Get twist stamped msg from smoother.