Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
truncate_path_local_action.cpp
1 // Copyright (c) 2021 RoboTech Vision
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <limits>
16 #include <memory>
17 #include <string>
18 #include <vector>
19 
20 #include "behaviortree_cpp_v3/decorator_node.h"
21 #include "geometry_msgs/msg/pose_stamped.hpp"
22 #include "nav2_util/geometry_utils.hpp"
23 #include "nav2_util/robot_utils.hpp"
24 #include "nav_msgs/msg/path.hpp"
25 #include "tf2_ros/create_timer_ros.h"
26 
27 #include "nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp"
28 
29 namespace nav2_behavior_tree
30 {
31 
33  const std::string & name,
34  const BT::NodeConfiguration & conf)
35 : BT::ActionNodeBase(name, conf)
36 {
37  tf_buffer_ =
38  config().blackboard->template get<std::shared_ptr<tf2_ros::Buffer>>(
39  "tf_buffer");
40 }
41 
42 inline BT::NodeStatus TruncatePathLocal::tick()
43 {
44  setStatus(BT::NodeStatus::RUNNING);
45 
46  double distance_forward, distance_backward;
47  geometry_msgs::msg::PoseStamped pose;
48  double angular_distance_weight;
49  double max_robot_pose_search_dist;
50 
51  getInput("distance_forward", distance_forward);
52  getInput("distance_backward", distance_backward);
53  getInput("angular_distance_weight", angular_distance_weight);
54  getInput("max_robot_pose_search_dist", max_robot_pose_search_dist);
55 
56  bool path_pruning = std::isfinite(max_robot_pose_search_dist);
57  nav_msgs::msg::Path new_path;
58  getInput("input_path", new_path);
59  if (!path_pruning || new_path != path_) {
60  path_ = new_path;
61  closest_pose_detection_begin_ = path_.poses.begin();
62  }
63 
64  if (!getRobotPose(path_.header.frame_id, pose)) {
65  return BT::NodeStatus::FAILURE;
66  }
67 
68  if (path_.poses.empty()) {
69  setOutput("output_path", path_);
70  return BT::NodeStatus::SUCCESS;
71  }
72 
73  auto closest_pose_detection_end = path_.poses.end();
74  if (path_pruning) {
75  closest_pose_detection_end = nav2_util::geometry_utils::first_after_integrated_distance(
76  closest_pose_detection_begin_, path_.poses.end(), max_robot_pose_search_dist);
77  }
78 
79  // find the closest pose on the path
80  auto current_pose = nav2_util::geometry_utils::min_by(
81  closest_pose_detection_begin_, closest_pose_detection_end,
82  [&pose, angular_distance_weight](const geometry_msgs::msg::PoseStamped & ps) {
83  return poseDistance(pose, ps, angular_distance_weight);
84  });
85 
86  if (path_pruning) {
87  closest_pose_detection_begin_ = current_pose;
88  }
89 
90  // expand forwards to extract desired length
91  auto forward_pose_it = nav2_util::geometry_utils::first_after_integrated_distance(
92  current_pose, path_.poses.end(), distance_forward);
93 
94  // expand backwards to extract desired length
95  // Note: current_pose + 1 is used because reverse iterator points to a cell before it
96  auto backward_pose_it = nav2_util::geometry_utils::first_after_integrated_distance(
97  std::reverse_iterator(current_pose + 1), path_.poses.rend(), distance_backward);
98 
99  nav_msgs::msg::Path output_path;
100  output_path.header = path_.header;
101  output_path.poses = std::vector<geometry_msgs::msg::PoseStamped>(
102  backward_pose_it.base(), forward_pose_it);
103  setOutput("output_path", output_path);
104 
105  return BT::NodeStatus::SUCCESS;
106 }
107 
108 inline bool TruncatePathLocal::getRobotPose(
109  std::string path_frame_id, geometry_msgs::msg::PoseStamped & pose)
110 {
111  if (!getInput("pose", pose)) {
112  std::string robot_frame;
113  if (!getInput("robot_frame", robot_frame)) {
114  RCLCPP_ERROR(
115  config().blackboard->get<rclcpp::Node::SharedPtr>("node")->get_logger(),
116  "Neither pose nor robot_frame specified for %s", name().c_str());
117  return false;
118  }
119  double transform_tolerance;
120  getInput("transform_tolerance", transform_tolerance);
121  if (!nav2_util::getCurrentPose(
122  pose, *tf_buffer_, path_frame_id, robot_frame, transform_tolerance))
123  {
124  RCLCPP_WARN(
125  config().blackboard->get<rclcpp::Node::SharedPtr>("node")->get_logger(),
126  "Failed to lookup current robot pose for %s", name().c_str());
127  return false;
128  }
129  }
130  return true;
131 }
132 
133 double
134 TruncatePathLocal::poseDistance(
135  const geometry_msgs::msg::PoseStamped & pose1,
136  const geometry_msgs::msg::PoseStamped & pose2,
137  const double angular_distance_weight)
138 {
139  double dx = pose1.pose.position.x - pose2.pose.position.x;
140  double dy = pose1.pose.position.y - pose2.pose.position.y;
141  // taking angular distance into account in addition to spatial distance
142  // (to improve picking a correct pose near cusps and loops)
143  tf2::Quaternion q1;
144  tf2::convert(pose1.pose.orientation, q1);
145  tf2::Quaternion q2;
146  tf2::convert(pose2.pose.orientation, q2);
147  double da = angular_distance_weight * std::abs(q1.angleShortestPath(q2));
148  return std::sqrt(dx * dx + dy * dy + da * da);
149 }
150 
151 } // namespace nav2_behavior_tree
152 
153 #include "behaviortree_cpp_v3/bt_factory.h"
154 BT_REGISTER_NODES(factory) {
155  factory.registerNodeType<nav2_behavior_tree::TruncatePathLocal>(
156  "TruncatePathLocal");
157 }
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.