21 #include "behaviortree_cpp/decorator_node.h"
22 #include "geometry_msgs/msg/pose_stamped.hpp"
23 #include "nav2_util/geometry_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
25 #include "nav_msgs/msg/path.hpp"
26 #include "rclcpp/rclcpp.hpp"
27 #include "tf2/LinearMath/Quaternion.hpp"
28 #include "tf2_ros/buffer.h"
29 #include "tf2_ros/create_timer_ros.h"
31 #include "nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp"
33 namespace nav2_behavior_tree
37 const std::string & name,
38 const BT::NodeConfiguration & conf)
39 : BT::ActionNodeBase(name, conf)
42 config().blackboard->template get<std::shared_ptr<tf2_ros::Buffer>>(
46 inline BT::NodeStatus TruncatePathLocal::tick()
48 setStatus(BT::NodeStatus::RUNNING);
50 double distance_forward, distance_backward;
51 geometry_msgs::msg::PoseStamped pose;
52 double angular_distance_weight;
53 double max_robot_pose_search_dist;
55 getInput(
"distance_forward", distance_forward);
56 getInput(
"distance_backward", distance_backward);
57 getInput(
"angular_distance_weight", angular_distance_weight);
58 getInput(
"max_robot_pose_search_dist", max_robot_pose_search_dist);
60 bool path_pruning = std::isfinite(max_robot_pose_search_dist);
61 nav_msgs::msg::Path new_path;
62 getInput(
"input_path", new_path);
63 if (!path_pruning || new_path != path_) {
65 closest_pose_detection_begin_ = path_.poses.begin();
68 if (!getRobotPose(path_.header.frame_id, pose)) {
69 return BT::NodeStatus::FAILURE;
72 if (path_.poses.empty()) {
73 setOutput(
"output_path", path_);
74 return BT::NodeStatus::SUCCESS;
77 auto closest_pose_detection_end = path_.poses.end();
79 closest_pose_detection_end = nav2_util::geometry_utils::first_after_integrated_distance(
80 closest_pose_detection_begin_, path_.poses.end(), max_robot_pose_search_dist);
84 auto current_pose = nav2_util::geometry_utils::min_by(
85 closest_pose_detection_begin_, closest_pose_detection_end,
86 [&pose, angular_distance_weight](
const geometry_msgs::msg::PoseStamped & ps) {
87 return poseDistance(pose, ps, angular_distance_weight);
91 closest_pose_detection_begin_ = current_pose;
95 auto forward_pose_it = nav2_util::geometry_utils::first_after_integrated_distance(
96 current_pose, path_.poses.end(), distance_forward);
100 auto backward_pose_it = nav2_util::geometry_utils::first_after_integrated_distance(
101 std::reverse_iterator(current_pose + 1), path_.poses.rend(), distance_backward);
103 nav_msgs::msg::Path output_path;
104 output_path.header = path_.header;
105 output_path.poses = std::vector<geometry_msgs::msg::PoseStamped>(
106 backward_pose_it.base(), forward_pose_it);
107 setOutput(
"output_path", output_path);
109 return BT::NodeStatus::SUCCESS;
112 inline bool TruncatePathLocal::getRobotPose(
113 std::string path_frame_id, geometry_msgs::msg::PoseStamped & pose)
115 if (!getInput(
"pose", pose)) {
116 std::string robot_frame;
117 if (!getInput(
"robot_frame", robot_frame)) {
119 config().blackboard->get<rclcpp::Node::SharedPtr>(
"node")->get_logger(),
120 "Neither pose nor robot_frame specified for %s", name().c_str());
123 double transform_tolerance;
124 getInput(
"transform_tolerance", transform_tolerance);
125 if (!nav2_util::getCurrentPose(
126 pose, *tf_buffer_, path_frame_id, robot_frame, transform_tolerance))
129 config().blackboard->get<rclcpp::Node::SharedPtr>(
"node")->get_logger(),
130 "Failed to lookup current robot pose for %s", name().c_str());
138 TruncatePathLocal::poseDistance(
139 const geometry_msgs::msg::PoseStamped & pose1,
140 const geometry_msgs::msg::PoseStamped & pose2,
141 const double angular_distance_weight)
143 double dx = pose1.pose.position.x - pose2.pose.position.x;
144 double dy = pose1.pose.position.y - pose2.pose.position.y;
148 tf2::convert(pose1.pose.orientation, q1);
150 tf2::convert(pose2.pose.orientation, q2);
151 double da = angular_distance_weight * std::abs(q1.angleShortestPath(q2));
152 return std::sqrt(dx * dx + dy * dy + da * da);
157 #include "behaviortree_cpp/bt_factory.h"
158 BT_REGISTER_NODES(factory) {
160 "TruncatePathLocal");
A BT::ActionNodeBase to shorten path to some distance around robot.
TruncatePathLocal(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A nav2_behavior_tree::TruncatePathLocal constructor.