Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
navfn_planner.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2018 Simbe Robotics
3 // Copyright (c) 2019 Samsung Research America
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 // Navigation Strategy based on:
18 // Brock, O. and Oussama K. (1999). High-Speed Navigation Using
19 // the Global Dynamic Window Approach. IEEE.
20 // https://cs.stanford.edu/group/manips/publications/pdfs/Brock_1999_ICRA.pdf
21 
22 // #define BENCHMARK_TESTING
23 
24 #include "nav2_navfn_planner/navfn_planner.hpp"
25 
26 #include <chrono>
27 #include <cmath>
28 #include <iomanip>
29 #include <iostream>
30 #include <limits>
31 #include <memory>
32 #include <string>
33 #include <vector>
34 
35 #include "builtin_interfaces/msg/duration.hpp"
36 #include "nav2_navfn_planner/navfn.hpp"
37 #include "nav2_util/costmap.hpp"
38 #include "nav2_util/node_utils.hpp"
39 #include "nav2_costmap_2d/cost_values.hpp"
40 
41 using namespace std::chrono_literals;
42 using namespace std::chrono; // NOLINT
43 using nav2_util::declare_parameter_if_not_declared;
44 using rcl_interfaces::msg::ParameterType;
45 using std::placeholders::_1;
46 
47 namespace nav2_navfn_planner
48 {
49 
50 NavfnPlanner::NavfnPlanner()
51 : tf_(nullptr), costmap_(nullptr)
52 {
53 }
54 
56 {
57  RCLCPP_INFO(
58  logger_, "Destroying plugin %s of type NavfnPlanner",
59  name_.c_str());
60 }
61 
62 void
64  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
65  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
66  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
67 {
68  tf_ = tf;
69  name_ = name;
70  costmap_ = costmap_ros->getCostmap();
71  global_frame_ = costmap_ros->getGlobalFrameID();
72 
73  node_ = parent;
74  auto node = parent.lock();
75  clock_ = node->get_clock();
76  logger_ = node->get_logger();
77 
78  RCLCPP_INFO(
79  logger_, "Configuring plugin %s of type NavfnPlanner",
80  name_.c_str());
81 
82  // Initialize parameters
83  // Declare this plugin's parameters
84  declare_parameter_if_not_declared(node, name + ".tolerance", rclcpp::ParameterValue(0.5));
85  node->get_parameter(name + ".tolerance", tolerance_);
86  declare_parameter_if_not_declared(node, name + ".use_astar", rclcpp::ParameterValue(false));
87  node->get_parameter(name + ".use_astar", use_astar_);
88  declare_parameter_if_not_declared(node, name + ".allow_unknown", rclcpp::ParameterValue(true));
89  node->get_parameter(name + ".allow_unknown", allow_unknown_);
90  declare_parameter_if_not_declared(
91  node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false));
92  node->get_parameter(name + ".use_final_approach_orientation", use_final_approach_orientation_);
93 
94  // Create a planner based on the new costmap size
95  planner_ = std::make_unique<NavFn>(
96  costmap_->getSizeInCellsX(),
97  costmap_->getSizeInCellsY());
98 }
99 
100 void
102 {
103  RCLCPP_INFO(
104  logger_, "Activating plugin %s of type NavfnPlanner",
105  name_.c_str());
106  // Add callback for dynamic parameters
107  auto node = node_.lock();
108  dyn_params_handler_ = node->add_on_set_parameters_callback(
109  std::bind(&NavfnPlanner::dynamicParametersCallback, this, _1));
110 }
111 
112 void
114 {
115  RCLCPP_INFO(
116  logger_, "Deactivating plugin %s of type NavfnPlanner",
117  name_.c_str());
118  dyn_params_handler_.reset();
119 }
120 
121 void
123 {
124  RCLCPP_INFO(
125  logger_, "Cleaning up plugin %s of type NavfnPlanner",
126  name_.c_str());
127  planner_.reset();
128 }
129 
130 nav_msgs::msg::Path NavfnPlanner::createPlan(
131  const geometry_msgs::msg::PoseStamped & start,
132  const geometry_msgs::msg::PoseStamped & goal)
133 {
134 #ifdef BENCHMARK_TESTING
135  steady_clock::time_point a = steady_clock::now();
136 #endif
137 
138  // Update planner based on the new costmap size
139  if (isPlannerOutOfDate()) {
140  planner_->setNavArr(
141  costmap_->getSizeInCellsX(),
142  costmap_->getSizeInCellsY());
143  }
144 
145  nav_msgs::msg::Path path;
146 
147  // Corner case of the start(x,y) = goal(x,y)
148  if (start.pose.position.x == goal.pose.position.x &&
149  start.pose.position.y == goal.pose.position.y)
150  {
151  unsigned int mx, my;
152  costmap_->worldToMap(start.pose.position.x, start.pose.position.y, mx, my);
153  if (costmap_->getCost(mx, my) == nav2_costmap_2d::LETHAL_OBSTACLE) {
154  RCLCPP_WARN(logger_, "Failed to create a unique pose path because of obstacles");
155  return path;
156  }
157  path.header.stamp = clock_->now();
158  path.header.frame_id = global_frame_;
159  geometry_msgs::msg::PoseStamped pose;
160  pose.header = path.header;
161  pose.pose.position.z = 0.0;
162 
163  pose.pose = start.pose;
164  // if we have a different start and goal orientation, set the unique path pose to the goal
165  // orientation, unless use_final_approach_orientation=true where we need it to be the start
166  // orientation to avoid movement from the local planner
167  if (start.pose.orientation != goal.pose.orientation && !use_final_approach_orientation_) {
168  pose.pose.orientation = goal.pose.orientation;
169  }
170  path.poses.push_back(pose);
171  return path;
172  }
173 
174  if (!makePlan(start.pose, goal.pose, tolerance_, path)) {
175  RCLCPP_WARN(
176  logger_, "%s: failed to create plan with "
177  "tolerance %.2f.", name_.c_str(), tolerance_);
178  }
179 
180 
181 #ifdef BENCHMARK_TESTING
182  steady_clock::time_point b = steady_clock::now();
183  duration<double> time_span = duration_cast<duration<double>>(b - a);
184  std::cout << "It took " << time_span.count() * 1000 << std::endl;
185 #endif
186 
187  return path;
188 }
189 
190 bool
192 {
193  if (!planner_.get() ||
194  planner_->nx != static_cast<int>(costmap_->getSizeInCellsX()) ||
195  planner_->ny != static_cast<int>(costmap_->getSizeInCellsY()))
196  {
197  return true;
198  }
199  return false;
200 }
201 
202 bool
204  const geometry_msgs::msg::Pose & start,
205  const geometry_msgs::msg::Pose & goal, double tolerance,
206  nav_msgs::msg::Path & plan)
207 {
208  // clear the plan, just in case
209  plan.poses.clear();
210 
211  plan.header.stamp = clock_->now();
212  plan.header.frame_id = global_frame_;
213 
214  double wx = start.position.x;
215  double wy = start.position.y;
216 
217  RCLCPP_DEBUG(
218  logger_, "Making plan from (%.2f,%.2f) to (%.2f,%.2f)",
219  start.position.x, start.position.y, goal.position.x, goal.position.y);
220 
221  unsigned int mx, my;
222  if (!worldToMap(wx, wy, mx, my)) {
223  RCLCPP_WARN(
224  logger_,
225  "Cannot create a plan: the robot's start position is off the global"
226  " costmap. Planning will always fail, are you sure"
227  " the robot has been properly localized?");
228  return false;
229  }
230 
231  // clear the starting cell within the costmap because we know it can't be an obstacle
232  clearRobotCell(mx, my);
233 
234  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
235 
236  // make sure to resize the underlying array that Navfn uses
237  planner_->setNavArr(
238  costmap_->getSizeInCellsX(),
239  costmap_->getSizeInCellsY());
240 
241  planner_->setCostmap(costmap_->getCharMap(), true, allow_unknown_);
242 
243  lock.unlock();
244 
245  int map_start[2];
246  map_start[0] = mx;
247  map_start[1] = my;
248 
249  wx = goal.position.x;
250  wy = goal.position.y;
251 
252  if (!worldToMap(wx, wy, mx, my)) {
253  RCLCPP_WARN(
254  logger_,
255  "The goal sent to the planner is off the global costmap."
256  " Planning will always fail to this goal.");
257  return false;
258  }
259 
260  int map_goal[2];
261  map_goal[0] = mx;
262  map_goal[1] = my;
263 
264  planner_->setStart(map_goal);
265  planner_->setGoal(map_start);
266  if (use_astar_) {
267  planner_->calcNavFnAstar();
268  } else {
269  planner_->calcNavFnDijkstra(true);
270  }
271 
272  double resolution = costmap_->getResolution();
273  geometry_msgs::msg::Pose p, best_pose;
274 
275  bool found_legal = false;
276 
277  p = goal;
278  double potential = getPointPotential(p.position);
279  if (potential < POT_HIGH) {
280  // Goal is reachable by itself
281  best_pose = p;
282  found_legal = true;
283  } else {
284  // Goal is not reachable. Trying to find nearest to the goal
285  // reachable point within its tolerance region
286  double best_sdist = std::numeric_limits<double>::max();
287 
288  p.position.y = goal.position.y - tolerance;
289  while (p.position.y <= goal.position.y + tolerance) {
290  p.position.x = goal.position.x - tolerance;
291  while (p.position.x <= goal.position.x + tolerance) {
292  potential = getPointPotential(p.position);
293  double sdist = squared_distance(p, goal);
294  if (potential < POT_HIGH && sdist < best_sdist) {
295  best_sdist = sdist;
296  best_pose = p;
297  found_legal = true;
298  }
299  p.position.x += resolution;
300  }
301  p.position.y += resolution;
302  }
303  }
304 
305  if (found_legal) {
306  // extract the plan
307  if (getPlanFromPotential(best_pose, plan)) {
308  smoothApproachToGoal(best_pose, plan);
309 
310  // If use_final_approach_orientation=true, interpolate the last pose orientation from the
311  // previous pose to set the orientation to the 'final approach' orientation of the robot so
312  // it does not rotate.
313  // And deal with corner case of plan of length 1
314  if (use_final_approach_orientation_) {
315  size_t plan_size = plan.poses.size();
316  if (plan_size == 1) {
317  plan.poses.back().pose.orientation = start.orientation;
318  } else if (plan_size > 1) {
319  double dx, dy, theta;
320  auto last_pose = plan.poses.back().pose.position;
321  auto approach_pose = plan.poses[plan_size - 2].pose.position;
322  // Deal with the case of NavFn producing a path with two equal last poses
323  if (std::abs(last_pose.x - approach_pose.x) < 0.0001 &&
324  std::abs(last_pose.y - approach_pose.y) < 0.0001 && plan_size > 2)
325  {
326  approach_pose = plan.poses[plan_size - 3].pose.position;
327  }
328  dx = last_pose.x - approach_pose.x;
329  dy = last_pose.y - approach_pose.y;
330  theta = atan2(dy, dx);
331  plan.poses.back().pose.orientation =
332  nav2_util::geometry_utils::orientationAroundZAxis(theta);
333  }
334  }
335  } else {
336  RCLCPP_ERROR(
337  logger_,
338  "Failed to create a plan from potential when a legal"
339  " potential was found. This shouldn't happen.");
340  }
341  }
342 
343  return !plan.poses.empty();
344 }
345 
346 void
348  const geometry_msgs::msg::Pose & goal,
349  nav_msgs::msg::Path & plan)
350 {
351  // Replace the last pose of the computed path if it's actually further away
352  // to the second to last pose than the goal pose.
353  if (plan.poses.size() >= 2) {
354  auto second_to_last_pose = plan.poses.end()[-2];
355  auto last_pose = plan.poses.back();
356  if (
357  squared_distance(last_pose.pose, second_to_last_pose.pose) >
358  squared_distance(goal, second_to_last_pose.pose))
359  {
360  plan.poses.back().pose = goal;
361  return;
362  }
363  }
364  geometry_msgs::msg::PoseStamped goal_copy;
365  goal_copy.pose = goal;
366  goal_copy.header = plan.header;
367  plan.poses.push_back(goal_copy);
368 }
369 
370 bool
372  const geometry_msgs::msg::Pose & goal,
373  nav_msgs::msg::Path & plan)
374 {
375  // clear the plan, just in case
376  plan.poses.clear();
377 
378  // Goal should be in global frame
379  double wx = goal.position.x;
380  double wy = goal.position.y;
381 
382  // the potential has already been computed, so we won't update our copy of the costmap
383  unsigned int mx, my;
384  if (!worldToMap(wx, wy, mx, my)) {
385  RCLCPP_WARN(
386  logger_,
387  "The goal sent to the navfn planner is off the global costmap."
388  " Planning will always fail to this goal.");
389  return false;
390  }
391 
392  int map_goal[2];
393  map_goal[0] = mx;
394  map_goal[1] = my;
395 
396  planner_->setStart(map_goal);
397 
398  const int & max_cycles = (costmap_->getSizeInCellsX() >= costmap_->getSizeInCellsY()) ?
399  (costmap_->getSizeInCellsX() * 4) : (costmap_->getSizeInCellsY() * 4);
400 
401  int path_len = planner_->calcPath(max_cycles);
402  if (path_len == 0) {
403  return false;
404  }
405 
406  auto cost = planner_->getLastPathCost();
407  RCLCPP_DEBUG(
408  logger_,
409  "Path found, %d steps, %f cost\n", path_len, cost);
410 
411  // extract the plan
412  float * x = planner_->getPathX();
413  float * y = planner_->getPathY();
414  int len = planner_->getPathLen();
415 
416  for (int i = len - 1; i >= 0; --i) {
417  // convert the plan to world coordinates
418  double world_x, world_y;
419  mapToWorld(x[i], y[i], world_x, world_y);
420 
421  geometry_msgs::msg::PoseStamped pose;
422  pose.header = plan.header;
423  pose.pose.position.x = world_x;
424  pose.pose.position.y = world_y;
425  pose.pose.position.z = 0.0;
426  pose.pose.orientation.x = 0.0;
427  pose.pose.orientation.y = 0.0;
428  pose.pose.orientation.z = 0.0;
429  pose.pose.orientation.w = 1.0;
430  plan.poses.push_back(pose);
431  }
432 
433  return !plan.poses.empty();
434 }
435 
436 double
437 NavfnPlanner::getPointPotential(const geometry_msgs::msg::Point & world_point)
438 {
439  unsigned int mx, my;
440  if (!worldToMap(world_point.x, world_point.y, mx, my)) {
441  return std::numeric_limits<double>::max();
442  }
443 
444  unsigned int index = my * planner_->nx + mx;
445  return planner_->potarr[index];
446 }
447 
448 // bool
449 // NavfnPlanner::validPointPotential(const geometry_msgs::msg::Point & world_point)
450 // {
451 // return validPointPotential(world_point, tolerance_);
452 // }
453 
454 // bool
455 // NavfnPlanner::validPointPotential(
456 // const geometry_msgs::msg::Point & world_point, double tolerance)
457 // {
458 // const double resolution = costmap_->getResolution();
459 
460 // geometry_msgs::msg::Point p = world_point;
461 // double potential = getPointPotential(p);
462 // if (potential < POT_HIGH) {
463 // // world_point is reachable by itself
464 // return true;
465 // } else {
466 // // world_point, is not reachable. Trying to find any
467 // // reachable point within its tolerance region
468 // p.y = world_point.y - tolerance;
469 // while (p.y <= world_point.y + tolerance) {
470 // p.x = world_point.x - tolerance;
471 // while (p.x <= world_point.x + tolerance) {
472 // potential = getPointPotential(p);
473 // if (potential < POT_HIGH) {
474 // return true;
475 // }
476 // p.x += resolution;
477 // }
478 // p.y += resolution;
479 // }
480 // }
481 
482 // return false;
483 // }
484 
485 bool
486 NavfnPlanner::worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my)
487 {
488  if (wx < costmap_->getOriginX() || wy < costmap_->getOriginY()) {
489  return false;
490  }
491 
492  mx = static_cast<int>(
493  std::round((wx - costmap_->getOriginX()) / costmap_->getResolution()));
494  my = static_cast<int>(
495  std::round((wy - costmap_->getOriginY()) / costmap_->getResolution()));
496 
497  if (mx < costmap_->getSizeInCellsX() && my < costmap_->getSizeInCellsY()) {
498  return true;
499  }
500 
501  RCLCPP_ERROR(
502  logger_,
503  "worldToMap failed: mx,my: %d,%d, size_x,size_y: %d,%d", mx, my,
504  costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());
505 
506  return false;
507 }
508 
509 void
510 NavfnPlanner::mapToWorld(double mx, double my, double & wx, double & wy)
511 {
512  wx = costmap_->getOriginX() + mx * costmap_->getResolution();
513  wy = costmap_->getOriginY() + my * costmap_->getResolution();
514 }
515 
516 void
517 NavfnPlanner::clearRobotCell(unsigned int mx, unsigned int my)
518 {
519  // TODO(orduno): check usage of this function, might instead be a request to
520  // world_model / map server
521  costmap_->setCost(mx, my, nav2_costmap_2d::FREE_SPACE);
522 }
523 
524 rcl_interfaces::msg::SetParametersResult
525 NavfnPlanner::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
526 {
527  rcl_interfaces::msg::SetParametersResult result;
528  for (auto parameter : parameters) {
529  const auto & type = parameter.get_type();
530  const auto & name = parameter.get_name();
531 
532  if (type == ParameterType::PARAMETER_DOUBLE) {
533  if (name == name_ + ".tolerance") {
534  tolerance_ = parameter.as_double();
535  }
536  } else if (type == ParameterType::PARAMETER_BOOL) {
537  if (name == name_ + ".use_astar") {
538  use_astar_ = parameter.as_bool();
539  } else if (name == name_ + ".allow_unknown") {
540  allow_unknown_ = parameter.as_bool();
541  } else if (name == name_ + ".use_final_approach_orientation") {
542  use_final_approach_orientation_ = parameter.as_bool();
543  }
544  }
545  }
546  result.successful = true;
547  return result;
548 }
549 
550 } // namespace nav2_navfn_planner
551 
552 #include "pluginlib/class_list_macros.hpp"
Abstract interface for global planners to adhere to with pluginlib.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:266
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:261
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:287
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:531
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:526
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:506
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:521
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition: costmap_2d.cpp:276
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override
Creating a plan from start and goal poses.
double squared_distance(const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2)
Compute the squared distance between two points.
bool makePlan(const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &goal, double tolerance, nav_msgs::msg::Path &plan)
Compute a plan given start and goal poses, provided in global world frame.
double getPointPotential(const geometry_msgs::msg::Point &world_point)
Compute the potential, or navigation cost, at a given point in the world must call computePotential f...
void activate() override
Activate lifecycle node.
void mapToWorld(double mx, double my, double &wx, double &wy)
Transform a point from map to world frame.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my)
Transform a point from world to map frame.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Configuring plugin.
bool isPlannerOutOfDate()
Determine if a new planner object should be made.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
void clearRobotCell(unsigned int mx, unsigned int my)
Set the corresponding cell cost to be free space.
void smoothApproachToGoal(const geometry_msgs::msg::Pose &goal, nav_msgs::msg::Path &plan)
Remove artifacts at the end of the path - originated from planning on a discretized world.
void cleanup() override
Cleanup lifecycle node.
void deactivate() override
Deactivate lifecycle node.
bool getPlanFromPotential(const geometry_msgs::msg::Pose &goal, nav_msgs::msg::Path &plan)
Compute a plan to a goal from a potential - must call computePotential first.