23
23
24
24
#include " geometry_msgs/msg/twist.hpp"
25
25
#include " geometry_msgs/msg/twist_stamped.hpp"
26
+ #include " rclcpp/create_subscription.hpp"
27
+ #include " rclcpp/node_interfaces/node_interfaces.hpp"
28
+ #include " rclcpp/node_interfaces/node_parameters_interface.hpp"
29
+ #include " rclcpp/node_interfaces/node_topics_interface.hpp"
26
30
#include " rclcpp/parameter_service.hpp"
27
31
#include " rclcpp/rclcpp.hpp"
28
32
#include " rclcpp/qos.hpp"
@@ -79,31 +83,56 @@ class TwistSubscriber
79
83
* @param TwistCallback The subscriber callback for Twist messages
80
84
* @param TwistStampedCallback The subscriber callback for TwistStamped messages
81
85
*/
82
- template <typename TwistCallbackT,
83
- typename TwistStampedCallbackT
84
- >
86
+ // template<typename TwistCallbackT,
87
+ // typename TwistStampedCallbackT
88
+ // >
89
+ // explicit TwistSubscriber(
90
+ // nav2_util::LifecycleNode::SharedPtr node,
91
+ // const std::string & topic,
92
+ // const rclcpp::QoS & qos,
93
+ // TwistCallbackT && TwistCallback,
94
+ // TwistStampedCallbackT && TwistStampedCallback
95
+ // )
96
+ // : TwistSubscriber(
97
+ // rclcpp::node_interfaces::NodeInterfaces<
98
+ // rclcpp::node_interfaces::NodeParametersInterface>(*node),
99
+ // topic, qos, std::forward<TwistCallbackT>(TwistCallback),
100
+ // std::forward<TwistStampedCallbackT>(TwistStampedCallback)) {}
101
+
102
+ /* *
103
+ * @brief A constructor that supports either Twist and TwistStamped
104
+ * @param node The node to add the Twist subscriber to
105
+ * @param topic The subscriber topic name
106
+ * @param qos The subscriber quality of service
107
+ * @param TwistCallback The subscriber callback for Twist messages
108
+ * @param TwistStampedCallback The subscriber callback for TwistStamped
109
+ * messages
110
+ */
111
+ template <typename TwistCallbackT, typename TwistStampedCallbackT>
85
112
explicit TwistSubscriber (
86
- nav2_util::LifecycleNode::SharedPtr node,
87
- const std::string & topic,
88
- const rclcpp::QoS & qos,
113
+ rclcpp::node_interfaces::NodeInterfaces<
114
+ rclcpp::node_interfaces::NodeParametersInterface,
115
+ rclcpp::node_interfaces::NodeTopicsInterface>
116
+ node,
117
+ const std::string & topic, const rclcpp::QoS & qos,
89
118
TwistCallbackT && TwistCallback,
90
- TwistStampedCallbackT && TwistStampedCallback
91
- )
119
+ TwistStampedCallbackT && TwistStampedCallback)
92
120
{
93
121
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_);
122
+ rclcpp::node_interfaces::NodeInterfaces<
123
+ rclcpp::node_interfaces::NodeParametersInterface>(node),
124
+ " enable_stamped_cmd_vel" , rclcpp::ParameterValue (false ));
125
+ is_stamped_ = node.get_node_parameters_interface ()
126
+ ->get_parameter (" enable_stamped_cmd_vel" )
127
+ .as_bool ();
97
128
if (is_stamped_) {
98
- twist_stamped_sub_ = node-> create_subscription <geometry_msgs::msg::TwistStamped>(
99
- topic,
100
- qos,
101
- std::forward<TwistStampedCallbackT>(TwistStampedCallback));
129
+ twist_stamped_sub_ =
130
+ rclcpp::create_subscription<geometry_msgs::msg::TwistStamped>(
131
+ node, topic, qos,
132
+ std::forward<TwistStampedCallbackT>(TwistStampedCallback));
102
133
} else {
103
- twist_sub_ = node->create_subscription <geometry_msgs::msg::Twist>(
104
- topic,
105
- qos,
106
- std::forward<TwistCallbackT>(TwistCallback));
134
+ twist_sub_ = rclcpp::create_subscription<geometry_msgs::msg::Twist>(
135
+ node, topic, qos, std::forward<TwistCallbackT>(TwistCallback));
107
136
}
108
137
}
109
138
@@ -115,23 +144,52 @@ class TwistSubscriber
115
144
* @param TwistStampedCallback The subscriber callback for TwistStamped messages
116
145
* @throw std::invalid_argument When configured with an invalid ROS parameter
117
146
*/
147
+ // template<typename TwistStampedCallbackT>
148
+ // explicit TwistSubscriber(
149
+ // nav2_util::LifecycleNode::SharedPtr node,
150
+ // const std::string & topic,
151
+ // const rclcpp::QoS & qos,
152
+ // TwistStampedCallbackT && TwistStampedCallback
153
+ // )
154
+ // : TwistSubscriber(
155
+ // rclcpp::node_interfaces::NodeInterfaces<
156
+ // rclcpp::node_interfaces::NodeParametersInterface>(*node),
157
+ // topic, qos,
158
+ // std::forward<TwistStampedCallbackT>(TwistStampedCallback)) {}
159
+
160
+ /* *
161
+ * @brief A constructor that only supports TwistStamped
162
+ * @param node The node to add the TwistStamped subscriber to
163
+ * @param topic The subscriber topic name
164
+ * @param qos The subscriber quality of service
165
+ * @param TwistStampedCallback The subscriber callback for TwistStamped
166
+ * messages
167
+ * @throw std::invalid_argument When configured with an invalid ROS parameter
168
+ */
118
169
template <typename TwistStampedCallbackT>
119
170
explicit TwistSubscriber (
120
- nav2_util::LifecycleNode::SharedPtr node,
121
- const std::string & topic,
122
- const rclcpp::QoS & qos,
123
- TwistStampedCallbackT && TwistStampedCallback
124
- )
171
+ rclcpp::node_interfaces::NodeInterfaces<
172
+ rclcpp::node_interfaces::NodeParametersInterface,
173
+ rclcpp::node_interfaces::NodeTopicsInterface>
174
+ node,
175
+ const std::string & topic, const rclcpp::QoS & qos,
176
+ TwistStampedCallbackT && TwistStampedCallback)
125
177
{
126
178
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_);
179
+ rclcpp::node_interfaces::NodeInterfaces<
180
+ rclcpp::node_interfaces::NodeParametersInterface>(node),
181
+ " enable_stamped_cmd_vel" , rclcpp::ParameterValue (false ));
182
+ is_stamped_ = node.get_node_parameters_interface ()
183
+ ->get_parameter (" enable_stamped_cmd_vel" )
184
+ .as_bool ();
130
185
if (is_stamped_) {
131
- twist_stamped_sub_ = node->create_subscription <geometry_msgs::msg::TwistStamped>(
132
- topic,
133
- qos,
134
- std::forward<TwistStampedCallbackT>(TwistStampedCallback));
186
+ twist_stamped_sub_ =
187
+ node.get_node_topics_interface ()->create_subscription (
188
+ topic,
189
+ rclcpp::create_subscription_factory<
190
+ geometry_msgs::msg::TwistStamped>(
191
+ std::forward<TwistStampedCallbackT>(TwistStampedCallback)),
192
+ qos);
135
193
} else {
136
194
throw std::invalid_argument (
137
195
" enable_stamped_cmd_vel must be true when using this constructor!" );
0 commit comments