Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
twist_subscriber.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_SUBSCRIBER_HPP_
17 #define NAV2_UTIL__TWIST_SUBSCRIBER_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 
72 {
73 public:
82  template<typename TwistCallbackT,
83  typename TwistStampedCallbackT
84  >
85  explicit TwistSubscriber(
86  nav2_util::LifecycleNode::SharedPtr node,
87  const std::string & topic,
88  const rclcpp::QoS & qos,
89  TwistCallbackT && TwistCallback,
90  TwistStampedCallbackT && TwistStampedCallback
91  )
92  {
93  nav2_util::declare_parameter_if_not_declared(
94  node, "enable_stamped_cmd_vel",
95  rclcpp::ParameterValue(true));
96  node->get_parameter("enable_stamped_cmd_vel", is_stamped_);
97  if (is_stamped_) {
98  twist_stamped_sub_ = node->create_subscription<geometry_msgs::msg::TwistStamped>(
99  topic,
100  qos,
101  std::forward<TwistStampedCallbackT>(TwistStampedCallback));
102  } else {
103  twist_sub_ = node->create_subscription<geometry_msgs::msg::Twist>(
104  topic,
105  qos,
106  std::forward<TwistCallbackT>(TwistCallback));
107  }
108  }
109 
118  template<typename TwistStampedCallbackT>
119  explicit TwistSubscriber(
120  nav2_util::LifecycleNode::SharedPtr node,
121  const std::string & topic,
122  const rclcpp::QoS & qos,
123  TwistStampedCallbackT && TwistStampedCallback
124  )
125  {
126  nav2_util::declare_parameter_if_not_declared(
127  node, "enable_stamped_cmd_vel",
128  rclcpp::ParameterValue(true));
129  node->get_parameter("enable_stamped_cmd_vel", is_stamped_);
130  if (is_stamped_) {
131  twist_stamped_sub_ = node->create_subscription<geometry_msgs::msg::TwistStamped>(
132  topic,
133  qos,
134  std::forward<TwistStampedCallbackT>(TwistStampedCallback));
135  } else {
136  throw std::invalid_argument(
137  "enable_stamped_cmd_vel must be true when using this constructor!");
138  }
139  }
140 
141 protected:
143  bool is_stamped_{true};
145  rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr twist_sub_ {nullptr};
147  rclcpp::Subscription<geometry_msgs::msg::TwistStamped>::SharedPtr twist_stamped_sub_ {nullptr};
148 };
149 
150 
151 } // namespace nav2_util
152 
153 #endif // NAV2_UTIL__TWIST_SUBSCRIBER_HPP_
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.