Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
bt_utils.hpp
1 // Copyright (c) 2018 Intel Corporation
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 #ifndef NAV2_BEHAVIOR_TREE__BT_UTILS_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_UTILS_HPP_
17 
18 #include <string>
19 #include <set>
20 #include <vector>
21 
22 #include "nav2_ros_common/lifecycle_node.hpp"
23 #include "behaviortree_cpp/behavior_tree.h"
24 #include "geometry_msgs/msg/point.hpp"
25 #include "geometry_msgs/msg/pose_stamped.hpp"
26 #include "geometry_msgs/msg/quaternion.hpp"
27 #include "nav_msgs/msg/path.hpp"
28 #include "nav_msgs/msg/goals.hpp"
29 #include "nav2_msgs/msg/waypoint_status.hpp"
30 
31 namespace BT
32 {
33 
34 // The follow templates are required when using these types as parameters
35 // in our BT XML files. They parse the strings in the XML into their corresponding
36 // data type.
37 
43 template<>
44 inline geometry_msgs::msg::Point convertFromString(const StringView key)
45 {
46  // if string starts with "json:{", try to parse it as json
47  if (StartWith(key, "json:")) {
48  auto new_key = key;
49  new_key.remove_prefix(5);
50  return convertFromJSON<geometry_msgs::msg::Point>(new_key);
51  }
52 
53  // three real numbers separated by semicolons
54  auto parts = BT::splitString(key, ';');
55  if (parts.size() != 3) {
56  throw std::runtime_error("invalid number of fields for point attribute)");
57  } else {
58  geometry_msgs::msg::Point position;
59  position.x = BT::convertFromString<double>(parts[0]);
60  position.y = BT::convertFromString<double>(parts[1]);
61  position.z = BT::convertFromString<double>(parts[2]);
62  return position;
63  }
64 }
65 
71 template<>
72 inline geometry_msgs::msg::Quaternion convertFromString(const StringView key)
73 {
74  // if string starts with "json:{", try to parse it as json
75  if (StartWith(key, "json:")) {
76  auto new_key = key;
77  new_key.remove_prefix(5);
78  return convertFromJSON<geometry_msgs::msg::Quaternion>(new_key);
79  }
80 
81  // four real numbers separated by semicolons
82  auto parts = BT::splitString(key, ';');
83  if (parts.size() != 4) {
84  throw std::runtime_error("invalid number of fields for orientation attribute)");
85  } else {
86  geometry_msgs::msg::Quaternion orientation;
87  orientation.x = BT::convertFromString<double>(parts[0]);
88  orientation.y = BT::convertFromString<double>(parts[1]);
89  orientation.z = BT::convertFromString<double>(parts[2]);
90  orientation.w = BT::convertFromString<double>(parts[3]);
91  return orientation;
92  }
93 }
94 
100 template<>
101 inline geometry_msgs::msg::PoseStamped convertFromString(const StringView key)
102 {
103  // if string starts with "json:{", try to parse it as json
104  if (StartWith(key, "json:")) {
105  auto new_key = key;
106  new_key.remove_prefix(5);
107  return convertFromJSON<geometry_msgs::msg::PoseStamped>(new_key);
108  }
109 
110  // 7 real numbers separated by semicolons
111  auto parts = BT::splitString(key, ';');
112  if (parts.size() != 9) {
113  throw std::runtime_error("invalid number of fields for PoseStamped attribute)");
114  } else {
115  geometry_msgs::msg::PoseStamped pose_stamped;
116  pose_stamped.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[0]));
117  pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[1]);
118  pose_stamped.pose.position.x = BT::convertFromString<double>(parts[2]);
119  pose_stamped.pose.position.y = BT::convertFromString<double>(parts[3]);
120  pose_stamped.pose.position.z = BT::convertFromString<double>(parts[4]);
121  pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[5]);
122  pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[6]);
123  pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[7]);
124  pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[8]);
125  return pose_stamped;
126  }
127 }
128 
134 template<>
135 inline std::vector<geometry_msgs::msg::PoseStamped> convertFromString(const StringView key)
136 {
137  // if string starts with "json:{", try to parse it as json
138  if (StartWith(key, "json:")) {
139  auto new_key = key;
140  new_key.remove_prefix(5);
141  return convertFromJSON<std::vector<geometry_msgs::msg::PoseStamped>>(new_key);
142  }
143 
144  auto parts = BT::splitString(key, ';');
145  if (parts.size() % 9 != 0) {
146  throw std::runtime_error("invalid number of fields for std::vector<PoseStamped> attribute)");
147  } else {
148  std::vector<geometry_msgs::msg::PoseStamped> poses;
149  for (size_t i = 0; i < parts.size(); i += 9) {
150  geometry_msgs::msg::PoseStamped pose_stamped;
151  pose_stamped.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[i]));
152  pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[i + 1]);
153  pose_stamped.pose.position.x = BT::convertFromString<double>(parts[i + 2]);
154  pose_stamped.pose.position.y = BT::convertFromString<double>(parts[i + 3]);
155  pose_stamped.pose.position.z = BT::convertFromString<double>(parts[i + 4]);
156  pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[i + 5]);
157  pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[i + 6]);
158  pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[i + 7]);
159  pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[i + 8]);
160  poses.push_back(pose_stamped);
161  }
162  return poses;
163  }
164 }
165 
171 template<>
172 inline nav_msgs::msg::Goals convertFromString(const StringView key)
173 {
174  // if string starts with "json:{", try to parse it as json
175  if (StartWith(key, "json:")) {
176  auto new_key = key;
177  new_key.remove_prefix(5);
178  return convertFromJSON<nav_msgs::msg::Goals>(new_key);
179  }
180 
181  auto parts = BT::splitString(key, ';');
182  if ((parts.size() - 2) % 9 != 0) {
183  throw std::runtime_error("invalid number of fields for Goals attribute)");
184  } else {
185  nav_msgs::msg::Goals goals_array;
186  goals_array.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[0]));
187  goals_array.header.frame_id = BT::convertFromString<std::string>(parts[1]);
188  for (size_t i = 2; i < parts.size(); i += 9) {
189  geometry_msgs::msg::PoseStamped pose_stamped;
190  pose_stamped.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[i]));
191  pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[i + 1]);
192  pose_stamped.pose.position.x = BT::convertFromString<double>(parts[i + 2]);
193  pose_stamped.pose.position.y = BT::convertFromString<double>(parts[i + 3]);
194  pose_stamped.pose.position.z = BT::convertFromString<double>(parts[i + 4]);
195  pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[i + 5]);
196  pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[i + 6]);
197  pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[i + 7]);
198  pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[i + 8]);
199  goals_array.goals.push_back(pose_stamped);
200  }
201  return goals_array;
202  }
203 }
204 
210 template<>
211 inline nav_msgs::msg::Path convertFromString(const StringView key)
212 {
213  // if string starts with "json:{", try to parse it as json
214  if (StartWith(key, "json:")) {
215  auto new_key = key;
216  new_key.remove_prefix(5);
217  return convertFromJSON<nav_msgs::msg::Path>(new_key);
218  }
219 
220  auto parts = BT::splitString(key, ';');
221  if ((parts.size() - 2) % 9 != 0) {
222  throw std::runtime_error("invalid number of fields for Path attribute)");
223  } else {
224  nav_msgs::msg::Path path;
225  path.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[0]));
226  path.header.frame_id = BT::convertFromString<std::string>(parts[1]);
227  for (size_t i = 2; i < parts.size(); i += 9) {
228  geometry_msgs::msg::PoseStamped pose_stamped;
229  path.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[i]));
230  pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[i + 1]);
231  pose_stamped.pose.position.x = BT::convertFromString<double>(parts[i + 2]);
232  pose_stamped.pose.position.y = BT::convertFromString<double>(parts[i + 3]);
233  pose_stamped.pose.position.z = BT::convertFromString<double>(parts[i + 4]);
234  pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[i + 5]);
235  pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[i + 6]);
236  pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[i + 7]);
237  pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[i + 8]);
238  path.poses.push_back(pose_stamped);
239  }
240  return path;
241  }
242 }
243 
249 template<>
250 inline nav2_msgs::msg::WaypointStatus convertFromString(const StringView key)
251 {
252  // if string starts with "json:{", try to parse it as json
253  if (StartWith(key, "json:")) {
254  auto new_key = key;
255  new_key.remove_prefix(5);
256  return convertFromJSON<nav2_msgs::msg::WaypointStatus>(new_key);
257  }
258 
259  auto parts = BT::splitString(key, ';');
260  if (parts.size() != 13) {
261  throw std::runtime_error("invalid number of fields for WaypointStatus attribute)");
262  } else {
263  nav2_msgs::msg::WaypointStatus waypoint_status;
264  waypoint_status.waypoint_status = BT::convertFromString<uint8_t>(parts[0]);
265  waypoint_status.waypoint_index = BT::convertFromString<uint32_t>(parts[1]);
266  waypoint_status.waypoint_pose.header.stamp =
267  rclcpp::Time(BT::convertFromString<int64_t>(parts[2]));
268  waypoint_status.waypoint_pose.header.frame_id = BT::convertFromString<std::string>(parts[3]);
269  waypoint_status.waypoint_pose.pose.position.x = BT::convertFromString<double>(parts[4]);
270  waypoint_status.waypoint_pose.pose.position.y = BT::convertFromString<double>(parts[5]);
271  waypoint_status.waypoint_pose.pose.position.z = BT::convertFromString<double>(parts[6]);
272  waypoint_status.waypoint_pose.pose.orientation.x = BT::convertFromString<double>(parts[7]);
273  waypoint_status.waypoint_pose.pose.orientation.y = BT::convertFromString<double>(parts[8]);
274  waypoint_status.waypoint_pose.pose.orientation.z = BT::convertFromString<double>(parts[9]);
275  waypoint_status.waypoint_pose.pose.orientation.w = BT::convertFromString<double>(parts[10]);
276  waypoint_status.error_code = BT::convertFromString<uint16_t>(parts[11]);
277  waypoint_status.error_msg = BT::convertFromString<std::string>(parts[12]);
278  return waypoint_status;
279  }
280 }
281 
287 template<>
288 inline std::vector<nav2_msgs::msg::WaypointStatus> convertFromString(const StringView key)
289 {
290  // if string starts with "json:{", try to parse it as json
291  if (StartWith(key, "json:")) {
292  auto new_key = key;
293  new_key.remove_prefix(5);
294  return convertFromJSON<std::vector<nav2_msgs::msg::WaypointStatus>>(new_key);
295  }
296 
297  auto parts = BT::splitString(key, ';');
298  if (parts.size() % 13 != 0) {
299  throw std::runtime_error("invalid number of fields for std::vector<WaypointStatus> attribute)");
300  } else {
301  std::vector<nav2_msgs::msg::WaypointStatus> wp_status_vector;
302  for (size_t i = 0; i < parts.size(); i += 13) {
303  nav2_msgs::msg::WaypointStatus wp_status;
304  wp_status.waypoint_status = BT::convertFromString<uint8_t>(parts[i]);
305  wp_status.waypoint_index = BT::convertFromString<uint32_t>(parts[i + 1]);
306  wp_status.waypoint_pose.header.stamp =
307  rclcpp::Time(BT::convertFromString<int64_t>(parts[i + 2]));
308  wp_status.waypoint_pose.header.frame_id = BT::convertFromString<std::string>(parts[i + 3]);
309  wp_status.waypoint_pose.pose.position.x = BT::convertFromString<double>(parts[i + 4]);
310  wp_status.waypoint_pose.pose.position.y = BT::convertFromString<double>(parts[i + 5]);
311  wp_status.waypoint_pose.pose.position.z = BT::convertFromString<double>(parts[i + 6]);
312  wp_status.waypoint_pose.pose.orientation.x = BT::convertFromString<double>(parts[i + 7]);
313  wp_status.waypoint_pose.pose.orientation.y = BT::convertFromString<double>(parts[i + 8]);
314  wp_status.waypoint_pose.pose.orientation.z = BT::convertFromString<double>(parts[i + 9]);
315  wp_status.waypoint_pose.pose.orientation.w = BT::convertFromString<double>(parts[i + 10]);
316  wp_status.error_code = BT::convertFromString<uint16_t>(parts[i + 11]);
317  wp_status.error_msg = BT::convertFromString<std::string>(parts[i + 12]);
318  wp_status_vector.push_back(wp_status);
319  }
320  return wp_status_vector;
321  }
322 }
323 
329 template<>
330 inline std::chrono::milliseconds convertFromString<std::chrono::milliseconds>(const StringView key)
331 {
332  // if string starts with "json:{", try to parse it as json
333  if (StartWith(key, "json:")) {
334  auto new_key = key;
335  new_key.remove_prefix(5);
336  return convertFromJSON<std::chrono::milliseconds>(new_key);
337  }
338 
339  return std::chrono::milliseconds(std::stoul(key.data()));
340 }
341 
349 template<typename T1, typename T2 = BT::TreeNode>
350 T1 deconflictPortAndParamFrame(
351  nav2::LifecycleNode::SharedPtr node,
352  std::string param_name,
353  const T2 * behavior_tree_node)
354 {
355  T1 param_value;
356  bool param_from_input = behavior_tree_node->getInput(param_name, param_value).has_value();
357 
358  if constexpr (std::is_same_v<T1, std::string>) {
359  // not valid if port doesn't exist or it is an empty string
360  param_from_input &= !param_value.empty();
361  }
362 
363  if (!param_from_input) {
364  RCLCPP_DEBUG(
365  node->get_logger(),
366  "Parameter '%s' not provided by behavior tree xml file, "
367  "using parameter from ros2 parameter file",
368  param_name.c_str());
369  node->get_parameter(param_name, param_value);
370  return param_value;
371  } else {
372  RCLCPP_DEBUG(
373  node->get_logger(),
374  "Parameter '%s' provided by behavior tree xml file",
375  param_name.c_str());
376  return param_value;
377  }
378 }
379 
391 template<typename T> inline
392 bool getInputPortOrBlackboard(
393  const BT::TreeNode & bt_node,
394  const BT::Blackboard & blackboard,
395  const std::string & param_name,
396  T & value)
397 {
398  if (bt_node.getInput<T>(param_name, value)) {
399  return true;
400  }
401  if (blackboard.get<T>(param_name, value)) {
402  return true;
403  }
404  return false;
405 }
406 
407 // Macro to remove boiler plate when using getInputPortOrBlackboard
408 #define getInputOrBlackboard(name, value) \
409  getInputPortOrBlackboard(*this, *(this->config().blackboard), name, value);
410 
411 } // namespace BT
412 
413 #endif // NAV2_BEHAVIOR_TREE__BT_UTILS_HPP_