Class OdomSmoother
Defined in File odometry_utils.hpp
Class Documentation
Wrapper for getting smooth odometry readings using a simple moving avergae. Subscribes to the topic with a mutex.
Public Functions
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
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
Get twist msg from smoother.
- Returns:
twist Twist msg
Get twist stamped msg from smoother.
- Returns:
twist TwistStamped msg
Protected Functions
Callback of odometry subscriber to process.
- Parameters:
msg – Odometry msg to smooth
Update internal state of the smoother after getting new data.
Protected Attributes