Nav2 Navigation Stack - kilted  kilted
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 "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"
29 
30 
31 namespace nav2_behavior_tree
32 {
33 
37 class TruncatePathLocal : public BT::ActionNodeBase
38 {
39 public:
46  const std::string & xml_tag_name,
47  const BT::NodeConfiguration & conf);
48 
53  static BT::PortsList providedPorts()
54  {
55  // Register JSON definitions for the types used in the ports
56  BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
57  BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
58 
59  return {
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"),
87  };
88  }
89 
90 private:
94  void halt() override {}
95 
100  BT::NodeStatus tick() override;
101 
108  bool getRobotPose(std::string path_frame_id, geometry_msgs::msg::PoseStamped & pose);
109 
118  static double poseDistance(
119  const geometry_msgs::msg::PoseStamped & pose1,
120  const geometry_msgs::msg::PoseStamped & pose2,
121  const double angular_distance_weight);
122 
123  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
124 
125  nav_msgs::msg::Path path_;
126  nav_msgs::msg::Path::_poses_type::iterator closest_pose_detection_begin_;
127 };
128 
129 } // namespace nav2_behavior_tree
130 
131 #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.