Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
path_handler.cpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 // Copyright (c) 2023 Dexory
3 // Copyright (c) 2023 Open Navigation LLC
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #include "nav2_mppi_controller/tools/path_handler.hpp"
18 #include "nav2_mppi_controller/tools/utils.hpp"
19 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
20 
21 namespace mppi
22 {
23 
25  rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name,
26  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap,
27  std::shared_ptr<tf2_ros::Buffer> buffer, ParametersHandler * param_handler)
28 {
29  name_ = name;
30  costmap_ = costmap;
31  tf_buffer_ = buffer;
32  auto node = parent.lock();
33  logger_ = node->get_logger();
34  parameters_handler_ = param_handler;
35 
36  auto getParam = parameters_handler_->getParamGetter(name_);
37  getParam(max_robot_pose_search_dist_, "max_robot_pose_search_dist", getMaxCostmapDist());
38  getParam(prune_distance_, "prune_distance", 1.5);
39  getParam(transform_tolerance_, "transform_tolerance", 0.1);
40  getParam(enforce_path_inversion_, "enforce_path_inversion", false);
41  if (enforce_path_inversion_) {
42  getParam(inversion_xy_tolerance_, "inversion_xy_tolerance", 0.2);
43  getParam(inversion_yaw_tolerance, "inversion_yaw_tolerance", 0.4);
44  inversion_locale_ = 0u;
45  }
46 }
47 
48 std::pair<nav_msgs::msg::Path, PathIterator>
50  const geometry_msgs::msg::PoseStamped & global_pose)
51 {
52  using nav2_util::geometry_utils::euclidean_distance;
53 
54  auto begin = global_plan_up_to_inversion_.poses.begin();
55 
56  // Limit the search for the closest pose up to max_robot_pose_search_dist on the path
57  auto closest_pose_upper_bound =
58  nav2_util::geometry_utils::first_after_integrated_distance(
59  global_plan_up_to_inversion_.poses.begin(), global_plan_up_to_inversion_.poses.end(),
60  max_robot_pose_search_dist_);
61 
62  // Find closest point to the robot
63  auto closest_point = nav2_util::geometry_utils::min_by(
64  begin, closest_pose_upper_bound,
65  [&global_pose](const geometry_msgs::msg::PoseStamped & ps) {
66  return euclidean_distance(global_pose, ps);
67  });
68 
69  nav_msgs::msg::Path transformed_plan;
70  transformed_plan.header.frame_id = costmap_->getGlobalFrameID();
71  transformed_plan.header.stamp = global_pose.header.stamp;
72 
73  auto pruned_plan_end =
74  nav2_util::geometry_utils::first_after_integrated_distance(
75  closest_point, global_plan_up_to_inversion_.poses.end(), prune_distance_);
76 
77  unsigned int mx, my;
78  // Find the furthest relevent pose on the path to consider within costmap
79  // bounds
80  // Transforming it to the costmap frame in the same loop
81  for (auto global_plan_pose = closest_point; global_plan_pose != pruned_plan_end;
82  ++global_plan_pose)
83  {
84  // Transform from global plan frame to costmap frame
85  geometry_msgs::msg::PoseStamped costmap_plan_pose;
86  global_plan_pose->header.stamp = global_pose.header.stamp;
87  global_plan_pose->header.frame_id = global_plan_.header.frame_id;
88  transformPose(costmap_->getGlobalFrameID(), *global_plan_pose, costmap_plan_pose);
89 
90  // Check if pose is inside the costmap
91  if (!costmap_->getCostmap()->worldToMap(
92  costmap_plan_pose.pose.position.x, costmap_plan_pose.pose.position.y, mx, my))
93  {
94  return {transformed_plan, closest_point};
95  }
96 
97  // Filling the transformed plan to return with the transformed pose
98  transformed_plan.poses.push_back(costmap_plan_pose);
99  }
100 
101  return {transformed_plan, closest_point};
102 }
103 
104 geometry_msgs::msg::PoseStamped PathHandler::transformToGlobalPlanFrame(
105  const geometry_msgs::msg::PoseStamped & pose)
106 {
107  if (global_plan_up_to_inversion_.poses.empty()) {
108  throw nav2_core::InvalidPath("Received plan with zero length");
109  }
110 
111  geometry_msgs::msg::PoseStamped robot_pose;
112  if (!transformPose(global_plan_up_to_inversion_.header.frame_id, pose, robot_pose)) {
114  "Unable to transform robot pose into global plan's frame");
115  }
116 
117  return robot_pose;
118 }
119 
120 nav_msgs::msg::Path PathHandler::transformPath(
121  const geometry_msgs::msg::PoseStamped & robot_pose)
122 {
123  // Find relevent bounds of path to use
124  geometry_msgs::msg::PoseStamped global_pose =
125  transformToGlobalPlanFrame(robot_pose);
126  auto [transformed_plan, lower_bound] = getGlobalPlanConsideringBoundsInCostmapFrame(global_pose);
127 
128  prunePlan(global_plan_up_to_inversion_, lower_bound);
129 
130  if (enforce_path_inversion_ && inversion_locale_ != 0u) {
131  if (isWithinInversionTolerances(global_pose)) {
132  prunePlan(global_plan_, global_plan_.poses.begin() + inversion_locale_);
133  global_plan_up_to_inversion_ = global_plan_;
134  inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
135  }
136  }
137 
138  if (transformed_plan.poses.empty()) {
139  throw nav2_core::InvalidPath("Resulting plan has 0 poses in it.");
140  }
141 
142  return transformed_plan;
143 }
144 
146  const std::string & frame, const geometry_msgs::msg::PoseStamped & in_pose,
147  geometry_msgs::msg::PoseStamped & out_pose) const
148 {
149  if (in_pose.header.frame_id == frame) {
150  out_pose = in_pose;
151  return true;
152  }
153 
154  try {
155  tf_buffer_->transform(
156  in_pose, out_pose, frame,
157  tf2::durationFromSec(transform_tolerance_));
158  out_pose.header.frame_id = frame;
159  return true;
160  } catch (tf2::TransformException & ex) {
161  RCLCPP_ERROR(logger_, "Exception in transformPose: %s", ex.what());
162  }
163  return false;
164 }
165 
167 {
168  const auto & costmap = costmap_->getCostmap();
169  return static_cast<double>(std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY())) *
170  costmap->getResolution() * 0.50;
171 }
172 
173 void PathHandler::setPath(const nav_msgs::msg::Path & plan)
174 {
175  global_plan_ = plan;
176  global_plan_up_to_inversion_ = global_plan_;
177  if (enforce_path_inversion_) {
178  inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
179  }
180 }
181 
182 nav_msgs::msg::Path & PathHandler::getPath() {return global_plan_;}
183 
184 void PathHandler::prunePlan(nav_msgs::msg::Path & plan, const PathIterator end)
185 {
186  plan.poses.erase(plan.poses.begin(), end);
187 }
188 
189 geometry_msgs::msg::PoseStamped PathHandler::getTransformedGoal(
190  const builtin_interfaces::msg::Time & stamp)
191 {
192  auto goal = global_plan_.poses.back();
193  goal.header.frame_id = global_plan_.header.frame_id;
194  goal.header.stamp = stamp;
195  if (goal.header.frame_id.empty()) {
196  throw nav2_core::ControllerTFError("Goal pose has an empty frame_id");
197  }
198  geometry_msgs::msg::PoseStamped transformed_goal;
199  if (!transformPose(costmap_->getGlobalFrameID(), goal, transformed_goal)) {
200  throw nav2_core::ControllerTFError("Unable to transform goal pose into costmap frame");
201  }
202  return transformed_goal;
203 }
204 
205 bool PathHandler::isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped & robot_pose)
206 {
207  // Keep full path if we are within tolerance of the inversion pose
208  const auto last_pose = global_plan_up_to_inversion_.poses.back();
209  float distance = hypotf(
210  robot_pose.pose.position.x - last_pose.pose.position.x,
211  robot_pose.pose.position.y - last_pose.pose.position.y);
212 
213  float angle_distance = angles::shortest_angular_distance(
214  tf2::getYaw(robot_pose.pose.orientation),
215  tf2::getYaw(last_pose.pose.orientation));
216 
217  return distance <= inversion_xy_tolerance_ && fabs(angle_distance) <= inversion_yaw_tolerance;
218 }
219 
220 } // namespace mppi
Handles getting parameters and dynamic parmaeter changes.
auto getParamGetter(const std::string &ns)
Get an object to retreive parameters.
bool isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped &robot_pose)
Check if the robot pose is within the set inversion tolerances.
std::pair< nav_msgs::msg::Path, PathIterator > getGlobalPlanConsideringBoundsInCostmapFrame(const geometry_msgs::msg::PoseStamped &global_pose)
Get global plan within window of the local costmap size.
nav_msgs::msg::Path & getPath()
Get reference path.
void setPath(const nav_msgs::msg::Path &plan)
Set new reference path.
double getMaxCostmapDist()
Get largest dimension of costmap (radially)
geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time &stamp)
Get the global goal pose transformed to the local frame.
void prunePlan(nav_msgs::msg::Path &plan, const PathIterator end)
Prune a path to only interesting portions.
bool transformPose(const std::string &frame, const geometry_msgs::msg::PoseStamped &in_pose, geometry_msgs::msg::PoseStamped &out_pose) const
Transform a pose to another frame.
void initialize(rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >, std::shared_ptr< tf2_ros::Buffer >, ParametersHandler *)
Initialize path handler on bringup.
nav_msgs::msg::Path transformPath(const geometry_msgs::msg::PoseStamped &robot_pose)
transform global plan to local applying constraints, then prune global plan
geometry_msgs::msg::PoseStamped transformToGlobalPlanFrame(const geometry_msgs::msg::PoseStamped &pose)
Transform a pose to the global reference frame.