Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
truncate_path_local_action.hpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Francisco Martin Rico
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__TRUNCATE_PATH_LOCAL_ACTION_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__TRUNCATE_PATH_LOCAL_ACTION_HPP_
18 
19 #include <memory>
20 #include <string>
21 #include <limits>
22 
23 #include "nav_msgs/msg/path.hpp"
24 
25 #include "behaviortree_cpp_v3/action_node.h"
26 #include "tf2_ros/buffer.h"
27 
28 namespace nav2_behavior_tree
29 {
30 
34 class TruncatePathLocal : public BT::ActionNodeBase
35 {
36 public:
43  const std::string & xml_tag_name,
44  const BT::NodeConfiguration & conf);
45 
50  static BT::PortsList providedPorts()
51  {
52  return {
53  BT::InputPort<nav_msgs::msg::Path>("input_path", "Original Path"),
54  BT::OutputPort<nav_msgs::msg::Path>(
55  "output_path", "Path truncated to a certain distance around robot"),
56  BT::InputPort<double>(
57  "distance_forward", 8.0,
58  "Distance in forward direction"),
59  BT::InputPort<double>(
60  "distance_backward", 4.0,
61  "Distance in backward direction"),
62  BT::InputPort<std::string>(
63  "robot_frame", "base_link",
64  "Robot base frame id"),
65  BT::InputPort<double>(
66  "transform_tolerance", 0.2,
67  "Transform lookup tolerance"),
68  BT::InputPort<geometry_msgs::msg::PoseStamped>(
69  "pose", "Manually specified pose to be used"
70  "if overriding current robot pose"),
71  BT::InputPort<double>(
72  "angular_distance_weight", 0.0,
73  "Weight of angular distance relative to positional distance when finding which path "
74  "pose is closest to robot. Not applicable on paths without orientations assigned"),
75  BT::InputPort<double>(
76  "max_robot_pose_search_dist", std::numeric_limits<double>::infinity(),
77  "Maximum forward integrated distance along the path (starting from the last detected pose) "
78  "to bound the search for the closest pose to the robot. When set to infinity (default), "
79  "whole path is searched every time"),
80  };
81  }
82 
83 private:
87  void halt() override {}
88 
93  BT::NodeStatus tick() override;
94 
101  bool getRobotPose(std::string path_frame_id, geometry_msgs::msg::PoseStamped & pose);
102 
111  static double poseDistance(
112  const geometry_msgs::msg::PoseStamped & pose1,
113  const geometry_msgs::msg::PoseStamped & pose2,
114  const double angular_distance_weight);
115 
116  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
117 
118  nav_msgs::msg::Path path_;
119  nav_msgs::msg::Path::_poses_type::iterator closest_pose_detection_begin_;
120 };
121 
122 } // namespace nav2_behavior_tree
123 
124 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__TRUNCATE_PATH_LOCAL_ACTION_HPP_
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.