Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
A simple wrapper on a Twist subscriber that receives either geometry_msgs::msg::TwistStamped or geometry_msgs::msg::Twist. More...
#include <nav2_util/include/nav2_util/twist_subscriber.hpp>
Public Member Functions | |
template<typename TwistCallbackT , typename TwistStampedCallbackT > | |
TwistSubscriber (nav2::LifecycleNode::SharedPtr node, const std::string &topic, TwistCallbackT &&TwistCallback, TwistStampedCallbackT &&TwistStampedCallback, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS()) | |
A constructor that supports either Twist and TwistStamped. More... | |
template<typename TwistStampedCallbackT > | |
TwistSubscriber (nav2::LifecycleNode::SharedPtr node, const std::string &topic, TwistStampedCallbackT &&TwistStampedCallback, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS()) | |
A constructor that only supports TwistStamped. More... | |
Protected Attributes | |
bool | is_stamped_ {true} |
The user-configured value for ROS parameter enable_stamped_cmd_vel. | |
nav2::Subscription< geometry_msgs::msg::Twist >::SharedPtr | twist_sub_ {nullptr} |
The subscription when using Twist. | |
nav2::Subscription< geometry_msgs::msg::TwistStamped >::SharedPtr | twist_stamped_sub_ {nullptr} |
The subscription when using TwistStamped. | |
A simple wrapper on a Twist subscriber that receives either geometry_msgs::msg::TwistStamped or geometry_msgs::msg::Twist.
Definition at line 71 of file twist_subscriber.hpp.
|
inlineexplicit |
A constructor that supports either Twist and TwistStamped.
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 |
Definition at line 85 of file twist_subscriber.hpp.
References is_stamped_, twist_stamped_sub_, and twist_sub_.
|
inlineexplicit |
A constructor that only supports TwistStamped.
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 |
std::invalid_argument | When configured with an invalid ROS parameter |
Definition at line 119 of file twist_subscriber.hpp.
References is_stamped_, and twist_stamped_sub_.