19 #include "nav_msgs/msg/path.hpp"
20 #include "geometry_msgs/msg/pose_stamped.hpp"
21 #include "nav2_util/geometry_utils.hpp"
22 #include "behaviortree_cpp/decorator_node.h"
24 #include "nav2_behavior_tree/plugins/action/concatenate_paths_action.hpp"
26 namespace nav2_behavior_tree
30 const std::string & name,
31 const BT::NodeConfiguration & conf)
32 : BT::ActionNodeBase(name, conf)
36 inline BT::NodeStatus ConcatenatePaths::tick()
38 setStatus(BT::NodeStatus::RUNNING);
40 nav_msgs::msg::Path input_path1, input_path2;
41 getInput(
"input_path1", input_path1);
42 getInput(
"input_path2", input_path2);
44 if (input_path1.poses.empty() && input_path2.poses.empty()) {
46 config().blackboard->get<rclcpp::Node::SharedPtr>(
"node")->get_logger(),
47 "No input paths provided to concatenate. Both paths are empty.");
48 return BT::NodeStatus::FAILURE;
51 nav_msgs::msg::Path output_path;
52 output_path = input_path1;
53 if (input_path1.header != std_msgs::msg::Header()) {
54 output_path.header = input_path1.header;
55 }
else if (input_path2.header != std_msgs::msg::Header()) {
56 output_path.header = input_path2.header;
59 output_path.poses.insert(
60 output_path.poses.end(),
61 input_path2.poses.begin(),
62 input_path2.poses.end());
64 setOutput(
"output_path", output_path);
65 return BT::NodeStatus::SUCCESS;
70 #include "behaviortree_cpp/bt_factory.h"
71 BT_REGISTER_NODES(factory)
A BT::ActionNodeBase to shorten path by some distance.
ConcatenatePaths(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A nav2_behavior_tree::ConcatenatePaths constructor.