Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
A simple wrapper on a Twist publisher that provides either Twist or TwistStamped. More...
#include <nav2_util/include/nav2_util/twist_publisher.hpp>
Public Member Functions | |
TwistPublisher (nav2::LifecycleNode::SharedPtr node, const std::string &topic, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS()) | |
A constructor. More... | |
void | on_activate () |
void | on_deactivate () |
bool | is_activated () const |
void | publish (std::unique_ptr< geometry_msgs::msg::TwistStamped > velocity) |
size_t | get_subscription_count () const |
A simple wrapper on a Twist publisher that provides either Twist or TwistStamped.
The default is to publish Twist to preserve backwards compatibility, but it can be overridden using the "enable_stamped_cmd_vel" parameter to publish TwistStamped.
Definition at line 46 of file twist_publisher.hpp.
|
inlineexplicit |
A constructor.
nh | The node |
topic | publisher topic name |
qos | publisher quality of service |
Definition at line 55 of file twist_publisher.hpp.