15 #ifndef NAV2_BEHAVIOR_TREE__BT_UTILS_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_UTILS_HPP_
22 #include "rclcpp/time.hpp"
23 #include "rclcpp/node.hpp"
24 #include "behaviortree_cpp/behavior_tree.h"
25 #include "geometry_msgs/msg/point.hpp"
26 #include "geometry_msgs/msg/quaternion.hpp"
27 #include "geometry_msgs/msg/pose_stamped.hpp"
28 #include "nav_msgs/msg/path.hpp"
43 inline geometry_msgs::msg::Point convertFromString(
const StringView key)
46 auto parts = BT::splitString(key,
';');
47 if (parts.size() != 3) {
48 throw std::runtime_error(
"invalid number of fields for point attribute)");
50 geometry_msgs::msg::Point position;
51 position.x = BT::convertFromString<double>(parts[0]);
52 position.y = BT::convertFromString<double>(parts[1]);
53 position.z = BT::convertFromString<double>(parts[2]);
64 inline geometry_msgs::msg::Quaternion convertFromString(
const StringView key)
67 auto parts = BT::splitString(key,
';');
68 if (parts.size() != 4) {
69 throw std::runtime_error(
"invalid number of fields for orientation attribute)");
71 geometry_msgs::msg::Quaternion orientation;
72 orientation.x = BT::convertFromString<double>(parts[0]);
73 orientation.y = BT::convertFromString<double>(parts[1]);
74 orientation.z = BT::convertFromString<double>(parts[2]);
75 orientation.w = BT::convertFromString<double>(parts[3]);
86 inline geometry_msgs::msg::PoseStamped convertFromString(
const StringView key)
89 auto parts = BT::splitString(key,
';');
90 if (parts.size() != 9) {
91 throw std::runtime_error(
"invalid number of fields for PoseStamped attribute)");
93 geometry_msgs::msg::PoseStamped pose_stamped;
94 pose_stamped.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[0]));
95 pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[1]);
96 pose_stamped.pose.position.x = BT::convertFromString<double>(parts[2]);
97 pose_stamped.pose.position.y = BT::convertFromString<double>(parts[3]);
98 pose_stamped.pose.position.z = BT::convertFromString<double>(parts[4]);
99 pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[5]);
100 pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[6]);
101 pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[7]);
102 pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[8]);
113 inline std::vector<geometry_msgs::msg::PoseStamped> convertFromString(
const StringView key)
116 auto parts = BT::splitString(key,
';');
117 if (parts.size() % 9 != 0) {
118 throw std::runtime_error(
"invalid number of fields for std::vector<PoseStamped> attribute)");
120 std::vector<geometry_msgs::msg::PoseStamped> poses;
121 for (
size_t i = 0; i < parts.size(); i += 9) {
122 geometry_msgs::msg::PoseStamped pose_stamped;
123 pose_stamped.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[i]));
124 pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[i + 1]);
125 pose_stamped.pose.position.x = BT::convertFromString<double>(parts[i + 2]);
126 pose_stamped.pose.position.y = BT::convertFromString<double>(parts[i + 3]);
127 pose_stamped.pose.position.z = BT::convertFromString<double>(parts[i + 4]);
128 pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[i + 5]);
129 pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[i + 6]);
130 pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[i + 7]);
131 pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[i + 8]);
132 poses.push_back(pose_stamped);
144 inline nav_msgs::msg::Path convertFromString(
const StringView key)
147 auto parts = BT::splitString(key,
';');
148 if ((parts.size() - 2) % 9 != 0) {
149 throw std::runtime_error(
"invalid number of fields for Path attribute)");
151 nav_msgs::msg::Path path;
152 path.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[0]));
153 path.header.frame_id = BT::convertFromString<std::string>(parts[1]);
154 for (
size_t i = 2; i < parts.size(); i += 9) {
155 geometry_msgs::msg::PoseStamped pose_stamped;
156 path.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[i]));
157 pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[i + 1]);
158 pose_stamped.pose.position.x = BT::convertFromString<double>(parts[i + 2]);
159 pose_stamped.pose.position.y = BT::convertFromString<double>(parts[i + 3]);
160 pose_stamped.pose.position.z = BT::convertFromString<double>(parts[i + 4]);
161 pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[i + 5]);
162 pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[i + 6]);
163 pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[i + 7]);
164 pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[i + 8]);
165 path.poses.push_back(pose_stamped);
177 inline std::chrono::milliseconds convertFromString<std::chrono::milliseconds>(
const StringView key)
179 return std::chrono::milliseconds(std::stoul(key.data()));
188 inline std::set<int> convertFromString(StringView key)
191 auto parts = splitString(key,
';');
194 for (
const auto part : parts) {
195 set.insert(convertFromString<int>(part));
207 template<
typename T1,
typename T2 = BT::TreeNode>
208 T1 deconflictPortAndParamFrame(
209 rclcpp::Node::SharedPtr node,
210 std::string param_name,
211 const T2 * behavior_tree_node)
214 bool param_from_input = behavior_tree_node->getInput(param_name, param_value).has_value();
216 if constexpr (std::is_same_v<T1, std::string>) {
218 param_from_input &= !param_value.empty();
221 if (!param_from_input) {
224 "Parameter '%s' not provided by behavior tree xml file, "
225 "using parameter from ros2 parameter file",
227 node->get_parameter(param_name, param_value);
232 "Parameter '%s' provided by behavior tree xml file",
249 template<
typename T>
inline
250 bool getInputPortOrBlackboard(
251 const BT::TreeNode & bt_node,
252 const BT::Blackboard & blackboard,
253 const std::string & param_name,
256 if (bt_node.getInput<T>(param_name, value)) {
259 if (blackboard.get<T>(param_name, value)) {
266 #define getInputOrBlackboard(name, value) \
267 getInputPortOrBlackboard(*this, *(this->config().blackboard), name, value);