16 #ifndef NAV2_UTIL__TWIST_PUBLISHER_HPP_
17 #define NAV2_UTIL__TWIST_PUBLISHER_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"
56 nav2_util::LifecycleNode::SharedPtr node,
57 const std::string & topic,
58 const rclcpp::QoS & qos)
61 using nav2_util::declare_parameter_if_not_declared;
62 declare_parameter_if_not_declared(
63 node,
"enable_stamped_cmd_vel",
64 rclcpp::ParameterValue{
true});
65 node->get_parameter(
"enable_stamped_cmd_vel", is_stamped_);
67 twist_stamped_pub_ = node->create_publisher<geometry_msgs::msg::TwistStamped>(
71 twist_pub_ = node->create_publisher<geometry_msgs::msg::Twist>(
80 twist_stamped_pub_->on_activate();
82 twist_pub_->on_activate();
89 twist_stamped_pub_->on_deactivate();
91 twist_pub_->on_deactivate();
95 [[nodiscard]]
bool is_activated()
const
98 return twist_stamped_pub_->is_activated();
100 return twist_pub_->is_activated();
104 void publish(std::unique_ptr<geometry_msgs::msg::TwistStamped> velocity)
107 twist_stamped_pub_->publish(std::move(velocity));
109 auto twist_msg = std::make_unique<geometry_msgs::msg::Twist>(velocity->twist);
110 twist_pub_->publish(std::move(twist_msg));
114 [[nodiscard]]
size_t get_subscription_count()
const
117 return twist_stamped_pub_->get_subscription_count();
119 return twist_pub_->get_subscription_count();
125 bool is_stamped_{
true};
126 rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr twist_pub_;
127 rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>::SharedPtr
A simple wrapper on a Twist publisher that provides either Twist or TwistStamped.
TwistPublisher(nav2_util::LifecycleNode::SharedPtr node, const std::string &topic, const rclcpp::QoS &qos)
A constructor.