16 #ifndef NAV2_UTIL__TWIST_SUBSCRIBER_HPP_
17 #define NAV2_UTIL__TWIST_SUBSCRIBER_HPP_
24 #include "geometry_msgs/msg/twist.hpp"
25 #include "geometry_msgs/msg/twist_stamped.hpp"
26 #include "rclcpp/parameter_service.hpp"
27 #include "rclcpp/rclcpp.hpp"
28 #include "rclcpp/qos.hpp"
29 #include "rclcpp_lifecycle/lifecycle_publisher.hpp"
31 #include "lifecycle_node.hpp"
32 #include "node_utils.hpp"
82 template<
typename TwistCallbackT,
83 typename TwistStampedCallbackT
86 nav2_util::LifecycleNode::SharedPtr node,
87 const std::string & topic,
88 const rclcpp::QoS & qos,
89 TwistCallbackT && TwistCallback,
90 TwistStampedCallbackT && TwistStampedCallback
93 nav2_util::declare_parameter_if_not_declared(
94 node,
"enable_stamped_cmd_vel",
95 rclcpp::ParameterValue(
false));
96 node->get_parameter(
"enable_stamped_cmd_vel",
is_stamped_);
101 std::forward<TwistStampedCallbackT>(TwistStampedCallback));
103 twist_sub_ = node->create_subscription<geometry_msgs::msg::Twist>(
106 std::forward<TwistCallbackT>(TwistCallback));
118 template<
typename TwistStampedCallbackT>
120 nav2_util::LifecycleNode::SharedPtr node,
121 const std::string & topic,
122 const rclcpp::QoS & qos,
123 TwistStampedCallbackT && TwistStampedCallback
126 nav2_util::declare_parameter_if_not_declared(
127 node,
"enable_stamped_cmd_vel",
128 rclcpp::ParameterValue(
false));
129 node->get_parameter(
"enable_stamped_cmd_vel",
is_stamped_);
134 std::forward<TwistStampedCallbackT>(TwistStampedCallback));
136 throw std::invalid_argument(
137 "enable_stamped_cmd_vel must be true when using this constructor!");
145 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
twist_sub_ {
nullptr};
A simple wrapper on a Twist subscriber that receives either geometry_msgs::msg::TwistStamped or geome...
TwistSubscriber(nav2_util::LifecycleNode::SharedPtr node, const std::string &topic, const rclcpp::QoS &qos, TwistCallbackT &&TwistCallback, TwistStampedCallbackT &&TwistStampedCallback)
A constructor that supports either Twist and TwistStamped.
TwistSubscriber(nav2_util::LifecycleNode::SharedPtr node, const std::string &topic, const rclcpp::QoS &qos, TwistStampedCallbackT &&TwistStampedCallback)
A constructor that only supports TwistStamped.
rclcpp::Subscription< geometry_msgs::msg::Twist >::SharedPtr twist_sub_
The subscription when using Twist.
bool is_stamped_
The user-configured value for ROS parameter enable_stamped_cmd_vel.
rclcpp::Subscription< geometry_msgs::msg::TwistStamped >::SharedPtr twist_stamped_sub_
The subscription when using TwistStamped.