Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
#include <nav2_util/include/nav2_util/odometry_utils.hpp>
Public Member Functions | |
OdomSmoother (const rclcpp::Node::WeakPtr &parent, double filter_duration=0.3, const std::string &odom_topic="odom") | |
Constructor that subscribes to an Odometry topic. More... | |
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. More... | |
geometry_msgs::msg::Twist | getTwist () |
Get twist msg from smoother. More... | |
geometry_msgs::msg::TwistStamped | getTwistStamped () |
Get twist stamped msg from smoother. More... | |
Protected Member Functions | |
void | odomCallback (nav_msgs::msg::Odometry::SharedPtr msg) |
Callback of odometry subscriber to process. More... | |
void | updateState () |
Update internal state of the smoother after getting new data. | |
Wrapper for getting smooth odometry readings using a simple moving avergae. Subscribes to the topic with a mutex.
Definition at line 41 of file odometry_utils.hpp.
|
explicit |
Constructor that subscribes to an Odometry topic.
parent | NodeHandle for creating subscriber |
filter_duration | Duration for odom history (seconds) |
odom_topic | Topic on which odometry should be received |
Definition at line 26 of file odometry_utils.cpp.
References odomCallback().
|
explicit |
Overloadded Constructor for nav_util::LifecycleNode parent that subscribes to an Odometry topic.
parent | NodeHandle for creating subscriber |
filter_duration | Duration for odom history (seconds) |
odom_topic | Topic on which odometry should be received |
Definition at line 46 of file odometry_utils.cpp.
References odomCallback().
|
inline |
Get twist msg from smoother.
Definition at line 71 of file odometry_utils.hpp.
|
inline |
Get twist stamped msg from smoother.
Definition at line 77 of file odometry_utils.hpp.
|
protected |
Callback of odometry subscriber to process.
msg | Odometry msg to smooth |
Definition at line 66 of file odometry_utils.cpp.
References updateState().
Referenced by OdomSmoother().