16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__TRUNCATE_PATH_LOCAL_ACTION_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__TRUNCATE_PATH_LOCAL_ACTION_HPP_
23 #include "behaviortree_cpp/action_node.h"
24 #include "behaviortree_cpp/json_export.h"
25 #include "nav_msgs/msg/path.hpp"
26 #include "nav2_behavior_tree/bt_utils.hpp"
27 #include "nav2_behavior_tree/json_utils.hpp"
28 #include "tf2_ros/buffer.h"
31 namespace nav2_behavior_tree
46 const std::string & xml_tag_name,
47 const BT::NodeConfiguration & conf);
56 BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
57 BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
60 BT::InputPort<nav_msgs::msg::Path>(
"input_path",
"Original Path"),
61 BT::OutputPort<nav_msgs::msg::Path>(
62 "output_path",
"Path truncated to a certain distance around robot"),
63 BT::InputPort<double>(
64 "distance_forward", 8.0,
65 "Distance in forward direction"),
66 BT::InputPort<double>(
67 "distance_backward", 4.0,
68 "Distance in backward direction"),
69 BT::InputPort<std::string>(
70 "robot_frame",
"base_link",
71 "Robot base frame id"),
72 BT::InputPort<double>(
73 "transform_tolerance", 0.2,
74 "Transform lookup tolerance"),
75 BT::InputPort<geometry_msgs::msg::PoseStamped>(
76 "pose",
"Manually specified pose to be used"
77 "if overriding current robot pose"),
78 BT::InputPort<double>(
79 "angular_distance_weight", 0.0,
80 "Weight of angular distance relative to positional distance when finding which path "
81 "pose is closest to robot. Not applicable on paths without orientations assigned"),
82 BT::InputPort<double>(
83 "max_robot_pose_search_dist", std::numeric_limits<double>::infinity(),
84 "Maximum forward integrated distance along the path (starting from the last detected pose) "
85 "to bound the search for the closest pose to the robot. When set to infinity (default), "
86 "whole path is searched every time"),
94 void halt()
override {}
100 BT::NodeStatus tick()
override;
108 bool getRobotPose(std::string path_frame_id, geometry_msgs::msg::PoseStamped & pose);
118 static double poseDistance(
119 const geometry_msgs::msg::PoseStamped & pose1,
120 const geometry_msgs::msg::PoseStamped & pose2,
121 const double angular_distance_weight);
123 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
125 nav_msgs::msg::Path path_;
126 nav_msgs::msg::Path::_poses_type::iterator closest_pose_detection_begin_;
A BT::ActionNodeBase to shorten path to some distance around robot.
static BT::PortsList providedPorts()
Creates list of BT ports.
TruncatePathLocal(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A nav2_behavior_tree::TruncatePathLocal constructor.