Class TwistSubscriber

Class Documentation

class TwistSubscriber

Public Functions

template<typename TwistCallbackT, typename TwistStampedCallbackT>
inline explicit TwistSubscriber(const rclcpp::Node::SharedPtr &node, const std::string &topic, const rclcpp::QoS &qos, TwistCallbackT &&TwistCallback, TwistStampedCallbackT &&TwistStampedCallback)

A constructor that supports either Twist and TwistStamped.

Parameters:
  • node – The node to add the Twist subscriber to

  • topic – The subscriber topic name

  • qos – The subscriber quality of service

  • TwistCallback – The subscriber callback for Twist messages

  • TwistStampedCallback – The subscriber callback for TwistStamped messages

template<typename TwistStampedCallbackT>
inline explicit TwistSubscriber(const rclcpp::Node::SharedPtr &node, const std::string &topic, const rclcpp::QoS &qos, TwistStampedCallbackT &&TwistStampedCallback)

A constructor that only supports TwistStamped.

Parameters:
  • node – The node to add the TwistStamped subscriber to

  • topic – The subscriber topic name

  • qos – The subscriber quality of service

  • TwistStampedCallback – The subscriber callback for TwistStamped messages

Throws:

std::invalid_argument – When configured with an invalid ROS parameter

Protected Attributes

bool is_stamped_ = {false}

The user-configured value for ROS parameter enable_stamped_cmd_vel.

rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr twist_sub_ = {nullptr}

The subscription when using Twist.

rclcpp::Subscription<geometry_msgs::msg::TwistStamped>::SharedPtr twist_stamped_sub_ = {nullptr}

The subscription when using TwistStamped.