Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_util::TwistPublisher Class Reference

A simple wrapper on a Twist publisher that provides either Twist or TwistStamped. More...

#include <nav2_util/include/nav2_util/twist_publisher.hpp>

Collaboration diagram for nav2_util::TwistPublisher:
Collaboration graph
[legend]

Public Member Functions

 TwistPublisher (nav2_util::LifecycleNode::SharedPtr node, const std::string &topic, const rclcpp::QoS &qos)
 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
 

Protected Attributes

std::string topic_
 
bool is_stamped_
 
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::Twist >::SharedPtr twist_pub_
 
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::TwistStamped >::SharedPtr twist_stamped_pub_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ TwistPublisher()

nav2_util::TwistPublisher::TwistPublisher ( nav2_util::LifecycleNode::SharedPtr  node,
const std::string &  topic,
const rclcpp::QoS &  qos 
)
inlineexplicit

A constructor.

Parameters
nhThe node
topicpublisher topic name
qospublisher quality of service

Definition at line 55 of file twist_publisher.hpp.


The documentation for this class was generated from the following file: