Nav2 Navigation Stack - kilted  kilted
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  auto node = node_.lock();
119  if (dyn_params_handler_ && node) {
120  node->remove_on_set_parameters_callback(dyn_params_handler_.get());
121  }
122  dyn_params_handler_.reset();
123 }
124 
125 void
127 {
128  RCLCPP_INFO(
129  logger_, "Cleaning up plugin %s of type NavfnPlanner",
130  name_.c_str());
131  planner_.reset();
132 }
133 
134 nav_msgs::msg::Path NavfnPlanner::createPlan(
135  const geometry_msgs::msg::PoseStamped & start,
136  const geometry_msgs::msg::PoseStamped & goal,
137  std::function<bool()> cancel_checker)
138 {
139 #ifdef BENCHMARK_TESTING
140  steady_clock::time_point a = steady_clock::now();
141 #endif
142  unsigned int mx_start, my_start, mx_goal, my_goal;
143  if (!costmap_->worldToMap(start.pose.position.x, start.pose.position.y, mx_start, my_start)) {
145  "Start Coordinates of(" + std::to_string(start.pose.position.x) + ", " +
146  std::to_string(start.pose.position.y) + ") was outside bounds");
147  }
148 
149  if (!costmap_->worldToMap(goal.pose.position.x, goal.pose.position.y, mx_goal, my_goal)) {
151  "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " +
152  std::to_string(goal.pose.position.y) + ") was outside bounds");
153  }
154 
155  if (tolerance_ == 0 && costmap_->getCost(mx_goal, my_goal) == nav2_costmap_2d::LETHAL_OBSTACLE) {
157  "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " +
158  std::to_string(goal.pose.position.y) + ") was in lethal cost");
159  }
160 
161  // Update planner based on the new costmap size
162  if (isPlannerOutOfDate()) {
163  planner_->setNavArr(
164  costmap_->getSizeInCellsX(),
165  costmap_->getSizeInCellsY());
166  }
167 
168  nav_msgs::msg::Path path;
169 
170  // Corner case of the start(x,y) = goal(x,y)
171  if (start.pose.position.x == goal.pose.position.x &&
172  start.pose.position.y == goal.pose.position.y)
173  {
174  path.header.stamp = clock_->now();
175  path.header.frame_id = global_frame_;
176  geometry_msgs::msg::PoseStamped pose;
177  pose.header = path.header;
178  pose.pose.position.z = 0.0;
179 
180  pose.pose = start.pose;
181  // if we have a different start and goal orientation, set the unique path pose to the goal
182  // orientation, unless use_final_approach_orientation=true where we need it to be the start
183  // orientation to avoid movement from the local planner
184  if (start.pose.orientation != goal.pose.orientation && !use_final_approach_orientation_) {
185  pose.pose.orientation = goal.pose.orientation;
186  }
187  path.poses.push_back(pose);
188  return path;
189  }
190 
191  if (!makePlan(start.pose, goal.pose, tolerance_, cancel_checker, path)) {
193  "Failed to create plan with tolerance of: " + std::to_string(tolerance_) );
194  }
195 
196 
197 #ifdef BENCHMARK_TESTING
198  steady_clock::time_point b = steady_clock::now();
199  duration<double> time_span = duration_cast<duration<double>>(b - a);
200  std::cout << "It took " << time_span.count() * 1000 << std::endl;
201 #endif
202 
203  return path;
204 }
205 
206 bool
208 {
209  if (!planner_.get() ||
210  planner_->nx != static_cast<int>(costmap_->getSizeInCellsX()) ||
211  planner_->ny != static_cast<int>(costmap_->getSizeInCellsY()))
212  {
213  return true;
214  }
215  return false;
216 }
217 
218 bool
220  const geometry_msgs::msg::Pose & start,
221  const geometry_msgs::msg::Pose & goal, double tolerance,
222  std::function<bool()> cancel_checker,
223  nav_msgs::msg::Path & plan)
224 {
225  // clear the plan, just in case
226  plan.poses.clear();
227 
228  plan.header.stamp = clock_->now();
229  plan.header.frame_id = global_frame_;
230 
231  double wx = start.position.x;
232  double wy = start.position.y;
233 
234  RCLCPP_DEBUG(
235  logger_, "Making plan from (%.2f,%.2f) to (%.2f,%.2f)",
236  start.position.x, start.position.y, goal.position.x, goal.position.y);
237 
238  unsigned int mx, my;
239  worldToMap(wx, wy, mx, my);
240 
241  // clear the starting cell within the costmap because we know it can't be an obstacle
242  clearRobotCell(mx, my);
243 
244  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
245 
246  // make sure to resize the underlying array that Navfn uses
247  planner_->setNavArr(
248  costmap_->getSizeInCellsX(),
249  costmap_->getSizeInCellsY());
250 
251  planner_->setCostmap(costmap_->getCharMap(), true, allow_unknown_);
252 
253  lock.unlock();
254 
255  int map_start[2];
256  map_start[0] = mx;
257  map_start[1] = my;
258 
259  wx = goal.position.x;
260  wy = goal.position.y;
261 
262  worldToMap(wx, wy, mx, my);
263  int map_goal[2];
264  map_goal[0] = mx;
265  map_goal[1] = my;
266 
267  planner_->setStart(map_goal);
268  planner_->setGoal(map_start);
269  if (use_astar_) {
270  planner_->calcNavFnAstar(cancel_checker);
271  } else {
272  planner_->calcNavFnDijkstra(cancel_checker, true);
273  }
274 
275  double resolution = costmap_->getResolution();
276  geometry_msgs::msg::Pose p, best_pose;
277 
278  bool found_legal = false;
279 
280  p = goal;
281  double potential = getPointPotential(p.position);
282  if (potential < POT_HIGH) {
283  // Goal is reachable by itself
284  best_pose = p;
285  found_legal = true;
286  } else {
287  // Goal is not reachable. Trying to find nearest to the goal
288  // reachable point within its tolerance region
289  double best_sdist = std::numeric_limits<double>::max();
290 
291  p.position.y = goal.position.y - tolerance;
292  while (p.position.y <= goal.position.y + tolerance) {
293  p.position.x = goal.position.x - tolerance;
294  while (p.position.x <= goal.position.x + tolerance) {
295  potential = getPointPotential(p.position);
296  if (potential < POT_HIGH) {
297  double sdist = squared_distance(p, goal);
298  if (sdist < best_sdist) {
299  best_sdist = sdist;
300  best_pose = p;
301  found_legal = true;
302  }
303  }
304  p.position.x += resolution;
305  }
306  p.position.y += resolution;
307  }
308  }
309 
310  if (found_legal) {
311  // extract the plan
312  if (getPlanFromPotential(best_pose, plan)) {
313  smoothApproachToGoal(best_pose, plan);
314 
315  // If use_final_approach_orientation=true, interpolate the last pose orientation from the
316  // previous pose to set the orientation to the 'final approach' orientation of the robot so
317  // it does not rotate.
318  // And deal with corner case of plan of length 1
319  if (use_final_approach_orientation_) {
320  size_t plan_size = plan.poses.size();
321  if (plan_size == 1) {
322  plan.poses.back().pose.orientation = start.orientation;
323  } else if (plan_size > 1) {
324  double dx, dy, theta;
325  auto last_pose = plan.poses.back().pose.position;
326  auto approach_pose = plan.poses[plan_size - 2].pose.position;
327  // Deal with the case of NavFn producing a path with two equal last poses
328  if (std::abs(last_pose.x - approach_pose.x) < 0.0001 &&
329  std::abs(last_pose.y - approach_pose.y) < 0.0001 && plan_size > 2)
330  {
331  approach_pose = plan.poses[plan_size - 3].pose.position;
332  }
333  dx = last_pose.x - approach_pose.x;
334  dy = last_pose.y - approach_pose.y;
335  theta = atan2(dy, dx);
336  plan.poses.back().pose.orientation =
337  nav2_util::geometry_utils::orientationAroundZAxis(theta);
338  }
339  }
340  } else {
341  RCLCPP_ERROR(
342  logger_,
343  "Failed to create a plan from potential when a legal"
344  " potential was found. This shouldn't happen.");
345  }
346  }
347 
348  return !plan.poses.empty();
349 }
350 
351 void
353  const geometry_msgs::msg::Pose & goal,
354  nav_msgs::msg::Path & plan)
355 {
356  // Replace the last pose of the computed path if it's actually further away
357  // to the second to last pose than the goal pose.
358  if (plan.poses.size() >= 2) {
359  auto second_to_last_pose = plan.poses.end()[-2];
360  auto last_pose = plan.poses.back();
361  if (
362  squared_distance(last_pose.pose, second_to_last_pose.pose) >
363  squared_distance(goal, second_to_last_pose.pose))
364  {
365  plan.poses.back().pose = goal;
366  return;
367  }
368  }
369  geometry_msgs::msg::PoseStamped goal_copy;
370  goal_copy.pose = goal;
371  goal_copy.header = plan.header;
372  plan.poses.push_back(goal_copy);
373 }
374 
375 bool
377  const geometry_msgs::msg::Pose & goal,
378  nav_msgs::msg::Path & plan)
379 {
380  // clear the plan, just in case
381  plan.poses.clear();
382 
383  // Goal should be in global frame
384  double wx = goal.position.x;
385  double wy = goal.position.y;
386 
387  // the potential has already been computed, so we won't update our copy of the costmap
388  unsigned int mx, my;
389  worldToMap(wx, wy, mx, my);
390 
391  int map_goal[2];
392  map_goal[0] = mx;
393  map_goal[1] = my;
394 
395  planner_->setStart(map_goal);
396 
397  const int & max_cycles = (costmap_->getSizeInCellsX() >= costmap_->getSizeInCellsY()) ?
398  (costmap_->getSizeInCellsX() * 4) : (costmap_->getSizeInCellsY() * 4);
399 
400  int path_len = planner_->calcPath(max_cycles);
401  if (path_len == 0) {
402  return false;
403  }
404 
405  auto cost = planner_->getLastPathCost();
406  RCLCPP_DEBUG(
407  logger_,
408  "Path found, %d steps, %f cost\n", path_len, cost);
409 
410  // extract the plan
411  float * x = planner_->getPathX();
412  float * y = planner_->getPathY();
413  int len = planner_->getPathLen();
414 
415  for (int i = len - 1; i >= 0; --i) {
416  // convert the plan to world coordinates
417  double world_x, world_y;
418  mapToWorld(x[i], y[i], world_x, world_y);
419 
420  geometry_msgs::msg::PoseStamped pose;
421  pose.header = plan.header;
422  pose.pose.position.x = world_x;
423  pose.pose.position.y = world_y;
424  pose.pose.position.z = 0.0;
425  pose.pose.orientation.x = 0.0;
426  pose.pose.orientation.y = 0.0;
427  pose.pose.orientation.z = 0.0;
428  pose.pose.orientation.w = 1.0;
429  plan.poses.push_back(pose);
430  }
431 
432  return !plan.poses.empty();
433 }
434 
435 double
436 NavfnPlanner::getPointPotential(const geometry_msgs::msg::Point & world_point)
437 {
438  unsigned int mx, my;
439  if (!worldToMap(world_point.x, world_point.y, mx, my)) {
440  return std::numeric_limits<double>::max();
441  }
442 
443  unsigned int index = my * planner_->nx + mx;
444  return planner_->potarr[index];
445 }
446 
447 // bool
448 // NavfnPlanner::validPointPotential(const geometry_msgs::msg::Point & world_point)
449 // {
450 // return validPointPotential(world_point, tolerance_);
451 // }
452 
453 // bool
454 // NavfnPlanner::validPointPotential(
455 // const geometry_msgs::msg::Point & world_point, double tolerance)
456 // {
457 // const double resolution = costmap_->getResolution();
458 
459 // geometry_msgs::msg::Point p = world_point;
460 // double potential = getPointPotential(p);
461 // if (potential < POT_HIGH) {
462 // // world_point is reachable by itself
463 // return true;
464 // } else {
465 // // world_point, is not reachable. Trying to find any
466 // // reachable point within its tolerance region
467 // p.y = world_point.y - tolerance;
468 // while (p.y <= world_point.y + tolerance) {
469 // p.x = world_point.x - tolerance;
470 // while (p.x <= world_point.x + tolerance) {
471 // potential = getPointPotential(p);
472 // if (potential < POT_HIGH) {
473 // return true;
474 // }
475 // p.x += resolution;
476 // }
477 // p.y += resolution;
478 // }
479 // }
480 
481 // return false;
482 // }
483 
484 bool
485 NavfnPlanner::worldToMap(double wx, double wy, unsigned int & mx, unsigned int & my)
486 {
487  if (wx < costmap_->getOriginX() || wy < costmap_->getOriginY()) {
488  return false;
489  }
490 
491  mx = static_cast<int>(
492  std::round((wx - costmap_->getOriginX()) / costmap_->getResolution()));
493  my = static_cast<int>(
494  std::round((wy - costmap_->getOriginY()) / costmap_->getResolution()));
495 
496  if (mx < costmap_->getSizeInCellsX() && my < costmap_->getSizeInCellsY()) {
497  return true;
498  }
499 
500  RCLCPP_ERROR(
501  logger_,
502  "worldToMap failed: mx,my: %d,%d, size_x,size_y: %d,%d", mx, my,
503  costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());
504 
505  return false;
506 }
507 
508 void
509 NavfnPlanner::mapToWorld(double mx, double my, double & wx, double & wy)
510 {
511  wx = costmap_->getOriginX() + mx * costmap_->getResolution();
512  wy = costmap_->getOriginY() + my * costmap_->getResolution();
513 }
514 
515 void
516 NavfnPlanner::clearRobotCell(unsigned int mx, unsigned int my)
517 {
518  // TODO(orduno): check usage of this function, might instead be a request to
519  // world_model / map server
520  costmap_->setCost(mx, my, nav2_costmap_2d::FREE_SPACE);
521 }
522 
523 rcl_interfaces::msg::SetParametersResult
524 NavfnPlanner::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
525 {
526  rcl_interfaces::msg::SetParametersResult result;
527  for (auto parameter : parameters) {
528  const auto & param_type = parameter.get_type();
529  const auto & param_name = parameter.get_name();
530  if(param_name.find(name_ + ".") != 0) {
531  continue;
532  }
533  if (param_type == ParameterType::PARAMETER_DOUBLE) {
534  if (param_name == name_ + ".tolerance") {
535  tolerance_ = parameter.as_double();
536  }
537  } else if (param_type == ParameterType::PARAMETER_BOOL) {
538  if (param_name == name_ + ".use_astar") {
539  use_astar_ = parameter.as_bool();
540  } else if (param_name == name_ + ".allow_unknown") {
541  allow_unknown_ = parameter.as_bool();
542  } else if (param_name == name_ + ".use_final_approach_orientation") {
543  use_final_approach_orientation_ = parameter.as_bool();
544  }
545  }
546  }
547  result.successful = true;
548  return result;
549 }
550 
551 } // namespace nav2_navfn_planner
552 
553 #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:264
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:259
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:291
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:576
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:571
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:566
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition: costmap_2d.cpp:274
double squared_distance(const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2)
Compute the squared distance between two points.
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 makePlan(const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &goal, double tolerance, std::function< bool()> cancel_checker, nav_msgs::msg::Path &plan)
Compute a plan given start and goal poses, provided in global 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 parameter 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.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::function< bool()> cancel_checker) override
Creating a plan from start and goal poses.
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.