Class OdomSmoother

Class Documentation

class OdomSmoother

Wrapper for getting smooth odometry readings using a simple moving avergae. Subscribes to the topic with a mutex.

Public Functions

explicit OdomSmoother(const rclcpp::Node::WeakPtr &parent, double filter_duration = 0.3, const std::string &odom_topic = "odom")

Constructor that subscribes to an Odometry topic.

Parameters:
  • parent – NodeHandle for creating subscriber

  • filter_duration – Duration for odom history (seconds)

  • odom_topic – Topic on which odometry should be received

explicit OdomSmoother(const nav2_util::LifecycleNode::WeakPtr &parent, double filter_duration = 0.3, const std::string &odom_topic = "odom")

Overloadded Constructor for nav_util::LifecycleNode parent that subscribes to an Odometry topic.

Parameters:
  • parent – NodeHandle for creating subscriber

  • filter_duration – Duration for odom history (seconds)

  • odom_topic – Topic on which odometry should be received

inline geometry_msgs::msg::Twist getTwist()

Get twist msg from smoother.

Returns:

twist Twist msg

inline geometry_msgs::msg::TwistStamped getTwistStamped()

Get twist stamped msg from smoother.

Returns:

twist TwistStamped msg

Protected Functions

void odomCallback(nav_msgs::msg::Odometry::SharedPtr msg)

Callback of odometry subscriber to process.

Parameters:

msg – Odometry msg to smooth

void updateState()

Update internal state of the smoother after getting new data.

Protected Attributes

rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_
nav_msgs::msg::Odometry odom_cumulate_
geometry_msgs::msg::TwistStamped vel_smooth_
std::mutex odom_mutex_
rclcpp::Duration odom_history_duration_
std::deque<nav_msgs::msg::Odometry> odom_history_