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.hpp"
29 #include "nav2_ros_common/lifecycle_node.hpp"
32 namespace nav2_behavior_tree
47 const std::string & xml_tag_name,
48 const BT::NodeConfiguration & conf);
57 BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
58 BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
61 BT::InputPort<nav_msgs::msg::Path>(
"input_path",
"Original Path"),
62 BT::OutputPort<nav_msgs::msg::Path>(
63 "output_path",
"Path truncated to a certain distance around robot"),
64 BT::InputPort<double>(
65 "distance_forward", 8.0,
66 "Distance in forward direction"),
67 BT::InputPort<double>(
68 "distance_backward", 4.0,
69 "Distance in backward direction"),
70 BT::InputPort<std::string>(
71 "robot_frame",
"base_link",
72 "Robot base frame id"),
73 BT::InputPort<double>(
74 "transform_tolerance", 0.2,
75 "Transform lookup tolerance"),
76 BT::InputPort<geometry_msgs::msg::PoseStamped>(
77 "pose",
"Manually specified pose to be used"
78 "if overriding current robot pose"),
79 BT::InputPort<double>(
80 "angular_distance_weight", 0.0,
81 "Weight of angular distance relative to positional distance when finding which path "
82 "pose is closest to robot. Not applicable on paths without orientations assigned"),
83 BT::InputPort<double>(
84 "max_robot_pose_search_dist", std::numeric_limits<double>::infinity(),
85 "Maximum forward integrated distance along the path (starting from the last detected pose) "
86 "to bound the search for the closest pose to the robot. When set to infinity (default), "
87 "whole path is searched every time"),
95 void halt()
override {}
101 BT::NodeStatus tick()
override;
109 bool getRobotPose(std::string path_frame_id, geometry_msgs::msg::PoseStamped & pose);
119 static double poseDistance(
120 const geometry_msgs::msg::PoseStamped & pose1,
121 const geometry_msgs::msg::PoseStamped & pose2,
122 const double angular_distance_weight);
124 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
126 nav_msgs::msg::Path path_;
127 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.