Class TwistPublisher

Class Documentation

class TwistPublisher

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.

Public Functions

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

A constructor.

Parameters:
  • nh – The node

  • topic – publisher topic name

  • qos – publisher quality of service

inline void on_activate()
inline void on_deactivate()
inline bool is_activated() const
inline void publish(std::unique_ptr<geometry_msgs::msg::TwistStamped> velocity)
inline 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_