Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
twist_publisher.hpp
1 // Copyright (C) 2023 Ryan Friedman
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 
16 #ifndef NAV2_UTIL__TWIST_PUBLISHER_HPP_
17 #define NAV2_UTIL__TWIST_PUBLISHER_HPP_
18 
19 
20 #include <memory>
21 #include <string>
22 #include <utility>
23 
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"
30 
31 #include "lifecycle_node.hpp"
32 #include "node_utils.hpp"
33 
34 namespace nav2_util
35 {
36 
47 {
48 public:
55  explicit TwistPublisher(
56  nav2_util::LifecycleNode::SharedPtr node,
57  const std::string & topic,
58  const rclcpp::QoS & qos)
59  : topic_(topic)
60  {
61  using nav2_util::declare_parameter_if_not_declared;
62  declare_parameter_if_not_declared(
63  node, "enable_stamped_cmd_vel",
64  rclcpp::ParameterValue{false});
65  node->get_parameter("enable_stamped_cmd_vel", is_stamped_);
66  if (is_stamped_) {
67  twist_stamped_pub_ = node->create_publisher<geometry_msgs::msg::TwistStamped>(
68  topic_,
69  qos);
70  } else {
71  twist_pub_ = node->create_publisher<geometry_msgs::msg::Twist>(
72  topic_,
73  qos);
74  }
75  }
76 
77  void on_activate()
78  {
79  if (is_stamped_) {
80  twist_stamped_pub_->on_activate();
81  } else {
82  twist_pub_->on_activate();
83  }
84  }
85 
86  void on_deactivate()
87  {
88  if (is_stamped_) {
89  twist_stamped_pub_->on_deactivate();
90  } else {
91  twist_pub_->on_deactivate();
92  }
93  }
94 
95  [[nodiscard]] bool is_activated() const
96  {
97  if (is_stamped_) {
98  return twist_stamped_pub_->is_activated();
99  } else {
100  return twist_pub_->is_activated();
101  }
102  }
103 
104  void publish(std::unique_ptr<geometry_msgs::msg::TwistStamped> velocity)
105  {
106  if (is_stamped_) {
107  twist_stamped_pub_->publish(std::move(velocity));
108  } else {
109  auto twist_msg = std::make_unique<geometry_msgs::msg::Twist>(velocity->twist);
110  twist_pub_->publish(std::move(twist_msg));
111  }
112  }
113 
114  [[nodiscard]] size_t get_subscription_count() const
115  {
116  if (is_stamped_) {
117  return twist_stamped_pub_->get_subscription_count();
118  } else {
119  return twist_pub_->get_subscription_count();
120  }
121  }
122 
123 protected:
124  std::string topic_;
125  bool is_stamped_;
126  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr twist_pub_;
127  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>::SharedPtr
128  twist_stamped_pub_;
129 };
130 
131 } // namespace nav2_util
132 
133 #endif // NAV2_UTIL__TWIST_PUBLISHER_HPP_
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.