Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smac_planner_2d.cpp
1 // Copyright (c) 2020, Samsung Research America
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. Reserved.
14 
15 #include <string>
16 #include <memory>
17 #include <vector>
18 #include <limits>
19 #include <algorithm>
20 
21 #include "nav2_smac_planner/smac_planner_2d.hpp"
22 #include "nav2_util/geometry_utils.hpp"
23 
24 // #define BENCHMARK_TESTING
25 
26 namespace nav2_smac_planner
27 {
28 using namespace std::chrono; // NOLINT
29 using rcl_interfaces::msg::ParameterType;
30 using std::placeholders::_1;
31 
33 : _a_star(nullptr),
34  _collision_checker(nullptr, 1, nullptr),
35  _smoother(nullptr),
36  _costmap(nullptr),
37  _costmap_downsampler(nullptr)
38 {
39 }
40 
42 {
43  RCLCPP_INFO(
44  _logger, "Destroying plugin %s of type SmacPlanner2D",
45  _name.c_str());
46 }
47 
49  const nav2::LifecycleNode::WeakPtr & parent,
50  std::string name, std::shared_ptr<tf2_ros::Buffer>/*tf*/,
51  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
52 {
53  _node = parent;
54  auto node = parent.lock();
55  _logger = node->get_logger();
56  _clock = node->get_clock();
57  _costmap = costmap_ros->getCostmap();
58  _name = name;
59  _global_frame = costmap_ros->getGlobalFrameID();
60 
61  RCLCPP_INFO(_logger, "Configuring %s of type SmacPlanner2D", name.c_str());
62 
63  // General planner params
64  nav2::declare_parameter_if_not_declared(
65  node, name + ".tolerance", rclcpp::ParameterValue(0.125));
66  _tolerance = static_cast<float>(node->get_parameter(name + ".tolerance").as_double());
67  nav2::declare_parameter_if_not_declared(
68  node, name + ".downsample_costmap", rclcpp::ParameterValue(false));
69  node->get_parameter(name + ".downsample_costmap", _downsample_costmap);
70  nav2::declare_parameter_if_not_declared(
71  node, name + ".downsampling_factor", rclcpp::ParameterValue(1));
72  node->get_parameter(name + ".downsampling_factor", _downsampling_factor);
73  nav2::declare_parameter_if_not_declared(
74  node, name + ".cost_travel_multiplier", rclcpp::ParameterValue(1.0));
75  node->get_parameter(name + ".cost_travel_multiplier", _search_info.cost_penalty);
76 
77  nav2::declare_parameter_if_not_declared(
78  node, name + ".allow_unknown", rclcpp::ParameterValue(true));
79  node->get_parameter(name + ".allow_unknown", _allow_unknown);
80  nav2::declare_parameter_if_not_declared(
81  node, name + ".max_iterations", rclcpp::ParameterValue(1000000));
82  node->get_parameter(name + ".max_iterations", _max_iterations);
83  nav2::declare_parameter_if_not_declared(
84  node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
85  node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
86  nav2::declare_parameter_if_not_declared(
87  node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000));
88  node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval);
89  nav2::declare_parameter_if_not_declared(
90  node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false));
91  node->get_parameter(name + ".use_final_approach_orientation", _use_final_approach_orientation);
92 
93  nav2::declare_parameter_if_not_declared(
94  node, name + ".max_planning_time", rclcpp::ParameterValue(2.0));
95  node->get_parameter(name + ".max_planning_time", _max_planning_time);
96  // Note that we need to declare it here to prevent the parameter from being declared in the
97  // dynamic reconfigure callback
98  nav2::declare_parameter_if_not_declared(
99  node, "introspection_mode", rclcpp::ParameterValue("disabled"));
100 
101  _motion_model = MotionModel::TWOD;
102 
103  if (_max_on_approach_iterations <= 0) {
104  RCLCPP_INFO(
105  _logger, "On approach iteration selected as <= 0, "
106  "disabling tolerance and on approach iterations.");
107  _max_on_approach_iterations = std::numeric_limits<int>::max();
108  }
109 
110  if (_max_iterations <= 0) {
111  RCLCPP_INFO(
112  _logger, "maximum iteration selected as <= 0, "
113  "disabling maximum iterations.");
114  _max_iterations = std::numeric_limits<int>::max();
115  }
116 
117  // Initialize collision checker
118  _collision_checker = GridCollisionChecker(costmap_ros, 1 /*for 2D, most be 1*/, node);
119  _collision_checker.setFootprint(
120  costmap_ros->getRobotFootprint(),
121  true /*for 2D, most use radius*/,
122  0.0 /*for 2D cost at inscribed isn't relevant*/);
123 
124  // Initialize A* template
125  _a_star = std::make_unique<AStarAlgorithm<Node2D>>(_motion_model, _search_info);
126  _a_star->initialize(
127  _allow_unknown,
128  _max_iterations,
129  _max_on_approach_iterations,
130  _terminal_checking_interval,
131  _max_planning_time,
132  0.0 /*unused for 2D*/,
133  1.0 /*unused for 2D*/);
134 
135  // Initialize path smoother
136  SmootherParams params;
137  params.get(node, name);
138  params.holonomic_ = true; // So smoother will treat this as a grid search
139  _smoother = std::make_unique<Smoother>(params);
140  _smoother->initialize(1e-50 /*No valid minimum turning radius for 2D*/);
141 
142  // Initialize costmap downsampler
143  std::string topic_name = "downsampled_costmap";
144  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
145  _costmap_downsampler->on_configure(
146  node, _global_frame, topic_name, _costmap, _downsampling_factor);
147 
148  _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>("unsmoothed_plan");
149 
150  RCLCPP_INFO(
151  _logger, "Configured plugin %s of type SmacPlanner2D with "
152  "tolerance %.2f, maximum iterations %i, "
153  "max on approach iterations %i, and %s.",
154  _name.c_str(), _tolerance, _max_iterations, _max_on_approach_iterations,
155  _allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal");
156 }
157 
159 {
160  RCLCPP_INFO(
161  _logger, "Activating plugin %s of type SmacPlanner2D",
162  _name.c_str());
163  _raw_plan_publisher->on_activate();
164  if (_costmap_downsampler) {
165  _costmap_downsampler->on_activate();
166  }
167  auto node = _node.lock();
168  // Add callback for dynamic parameters
169  _dyn_params_handler = node->add_on_set_parameters_callback(
170  std::bind(&SmacPlanner2D::dynamicParametersCallback, this, _1));
171 }
172 
174 {
175  RCLCPP_INFO(
176  _logger, "Deactivating plugin %s of type SmacPlanner2D",
177  _name.c_str());
178  _raw_plan_publisher->on_deactivate();
179  if (_costmap_downsampler) {
180  _costmap_downsampler->on_deactivate();
181  }
182  // shutdown dyn_param_handler
183  auto node = _node.lock();
184  if (_dyn_params_handler && node) {
185  node->remove_on_set_parameters_callback(_dyn_params_handler.get());
186  }
187  _dyn_params_handler.reset();
188 }
189 
191 {
192  RCLCPP_INFO(
193  _logger, "Cleaning up plugin %s of type SmacPlanner2D",
194  _name.c_str());
195  _a_star.reset();
196  _smoother.reset();
197  if (_costmap_downsampler) {
198  _costmap_downsampler->on_cleanup();
199  _costmap_downsampler.reset();
200  }
201  _raw_plan_publisher.reset();
202 }
203 
204 nav_msgs::msg::Path SmacPlanner2D::createPlan(
205  const geometry_msgs::msg::PoseStamped & start,
206  const geometry_msgs::msg::PoseStamped & goal,
207  std::function<bool()> cancel_checker)
208 {
209  std::lock_guard<std::mutex> lock_reinit(_mutex);
210  steady_clock::time_point a = steady_clock::now();
211 
212  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
213 
214  // Downsample costmap, if required
215  nav2_costmap_2d::Costmap2D * costmap = _costmap;
216  if (_downsample_costmap && _downsampling_factor > 1) {
217  costmap = _costmap_downsampler->downsample(_downsampling_factor);
218  _collision_checker.setCostmap(costmap);
219  }
220 
221  // Set collision checker and costmap information
222  _a_star->setCollisionChecker(&_collision_checker);
223 
224  // Set starting point
225  float mx_start, my_start, mx_goal, my_goal;
226  if (!costmap->worldToMapContinuous(
227  start.pose.position.x,
228  start.pose.position.y,
229  mx_start,
230  my_start))
231  {
233  "Start Coordinates of(" + std::to_string(start.pose.position.x) + ", " +
234  std::to_string(start.pose.position.y) + ") was outside bounds");
235  }
236  _a_star->setStart(mx_start, my_start, 0);
237 
238  // Set goal point
239  if (!costmap->worldToMapContinuous(
240  goal.pose.position.x,
241  goal.pose.position.y,
242  mx_goal,
243  my_goal))
244  {
246  "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " +
247  std::to_string(goal.pose.position.y) + ") was outside bounds");
248  }
249  _a_star->setGoal(mx_goal, my_goal, 0);
250 
251  // Setup message
252  nav_msgs::msg::Path plan;
253  plan.header.stamp = _clock->now();
254  plan.header.frame_id = _global_frame;
255  geometry_msgs::msg::PoseStamped pose;
256  pose.header = plan.header;
257  pose.pose.position.z = 0.0;
258  pose.pose.orientation.x = 0.0;
259  pose.pose.orientation.y = 0.0;
260  pose.pose.orientation.z = 0.0;
261  pose.pose.orientation.w = 1.0;
262 
263  // Corner case of start and goal being on the same cell
264  if (std::floor(mx_start) == std::floor(mx_goal) && std::floor(my_start) == std::floor(my_goal)) {
265  pose.pose = start.pose;
266  // if we have a different start and goal orientation, set the unique path pose to the goal
267  // orientation, unless use_final_approach_orientation=true where we need it to be the start
268  // orientation to avoid movement from the local planner
269  if (start.pose.orientation != goal.pose.orientation && !_use_final_approach_orientation) {
270  pose.pose.orientation = goal.pose.orientation;
271  }
272  plan.poses.push_back(pose);
273 
274  // Publish raw path for debug
275  if (_raw_plan_publisher->get_subscription_count() > 0) {
276  _raw_plan_publisher->publish(plan);
277  }
278 
279  return plan;
280  }
281 
282  // Compute plan
283  Node2D::CoordinateVector path;
284  int num_iterations = 0;
285  // Note: All exceptions thrown are handled by the planner server and returned to the action
286  if (!_a_star->createPath(
287  path, num_iterations,
288  _tolerance / static_cast<float>(costmap->getResolution()), cancel_checker))
289  {
290  // Note: If the start is blocked only one iteration will occur before failure
291  if (num_iterations == 1) {
292  throw nav2_core::StartOccupied("Start occupied");
293  }
294 
295  if (num_iterations < _a_star->getMaxIterations()) {
296  throw nav2_core::NoValidPathCouldBeFound("no valid path found");
297  } else {
298  throw nav2_core::PlannerTimedOut("exceeded maximum iterations");
299  }
300  }
301 
302  // Convert to world coordinates
303  plan.poses.reserve(path.size());
304  for (int i = path.size() - 1; i >= 0; --i) {
305  pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
306  plan.poses.push_back(pose);
307  }
308 
309  // Publish raw path for debug
310  if (_raw_plan_publisher->get_subscription_count() > 0) {
311  _raw_plan_publisher->publish(plan);
312  }
313 
314  // Find how much time we have left to do smoothing
315  steady_clock::time_point b = steady_clock::now();
316  duration<double> time_span = duration_cast<duration<double>>(b - a);
317  double time_remaining = _max_planning_time - static_cast<double>(time_span.count());
318 
319 #ifdef BENCHMARK_TESTING
320  std::cout << "It took " << time_span.count() * 1000 <<
321  " milliseconds with " << num_iterations << " iterations." << std::endl;
322 #endif
323 
324  // Smooth plan
325  _smoother->smooth(plan, costmap, time_remaining);
326 
327  // If use_final_approach_orientation=true, interpolate the last pose orientation from the
328  // previous pose to set the orientation to the 'final approach' orientation of the robot so
329  // it does not rotate.
330  // And deal with corner case of plan of length 1
331  // If use_final_approach_orientation=false (default), override last pose orientation to match goal
332  size_t plan_size = plan.poses.size();
333  if (_use_final_approach_orientation) {
334  if (plan_size == 1) {
335  plan.poses.back().pose.orientation = start.pose.orientation;
336  } else if (plan_size > 1) {
337  double dx, dy, theta;
338  auto last_pose = plan.poses.back().pose.position;
339  auto approach_pose = plan.poses[plan_size - 2].pose.position;
340  dx = last_pose.x - approach_pose.x;
341  dy = last_pose.y - approach_pose.y;
342  theta = atan2(dy, dx);
343  plan.poses.back().pose.orientation =
344  nav2_util::geometry_utils::orientationAroundZAxis(theta);
345  }
346  } else if (plan_size > 0) {
347  plan.poses.back().pose.orientation = goal.pose.orientation;
348  }
349 
350  return plan;
351 }
352 
353 rcl_interfaces::msg::SetParametersResult
354 SmacPlanner2D::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
355 {
356  rcl_interfaces::msg::SetParametersResult result;
357  std::lock_guard<std::mutex> lock_reinit(_mutex);
358 
359  bool reinit_a_star = false;
360  bool reinit_downsampler = false;
361 
362  for (auto parameter : parameters) {
363  const auto & param_type = parameter.get_type();
364  const auto & param_name = parameter.get_name();
365  if(param_name.find(_name + ".") != 0) {
366  continue;
367  }
368  if (param_type == ParameterType::PARAMETER_DOUBLE) {
369  if (param_name == _name + ".tolerance") {
370  _tolerance = static_cast<float>(parameter.as_double());
371  } else if (param_name == _name + ".cost_travel_multiplier") {
372  reinit_a_star = true;
373  _search_info.cost_penalty = parameter.as_double();
374  } else if (param_name == _name + ".max_planning_time") {
375  reinit_a_star = true;
376  _max_planning_time = parameter.as_double();
377  }
378  } else if (param_type == ParameterType::PARAMETER_BOOL) {
379  if (param_name == _name + ".downsample_costmap") {
380  reinit_downsampler = true;
381  _downsample_costmap = parameter.as_bool();
382  } else if (param_name == _name + ".allow_unknown") {
383  reinit_a_star = true;
384  _allow_unknown = parameter.as_bool();
385  } else if (param_name == _name + ".use_final_approach_orientation") {
386  _use_final_approach_orientation = parameter.as_bool();
387  }
388  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
389  if (param_name == _name + ".downsampling_factor") {
390  reinit_downsampler = true;
391  _downsampling_factor = parameter.as_int();
392  } else if (param_name == _name + ".max_iterations") {
393  reinit_a_star = true;
394  _max_iterations = parameter.as_int();
395  if (_max_iterations <= 0) {
396  RCLCPP_INFO(
397  _logger, "maximum iteration selected as <= 0, "
398  "disabling maximum iterations.");
399  _max_iterations = std::numeric_limits<int>::max();
400  }
401  } else if (param_name == _name + ".max_on_approach_iterations") {
402  reinit_a_star = true;
403  _max_on_approach_iterations = parameter.as_int();
404  if (_max_on_approach_iterations <= 0) {
405  RCLCPP_INFO(
406  _logger, "On approach iteration selected as <= 0, "
407  "disabling tolerance and on approach iterations.");
408  _max_on_approach_iterations = std::numeric_limits<int>::max();
409  }
410  } else if (param_name == _name + ".terminal_checking_interval") {
411  reinit_a_star = true;
412  _terminal_checking_interval = parameter.as_int();
413  }
414  }
415  }
416 
417  // Re-init if needed with mutex lock (to avoid re-init while creating a plan)
418  if (reinit_a_star || reinit_downsampler) {
419  // Re-Initialize A* template
420  if (reinit_a_star) {
421  _a_star = std::make_unique<AStarAlgorithm<Node2D>>(_motion_model, _search_info);
422  _a_star->initialize(
423  _allow_unknown,
424  _max_iterations,
425  _max_on_approach_iterations,
426  _terminal_checking_interval,
427  _max_planning_time,
428  0.0 /*unused for 2D*/,
429  1.0 /*unused for 2D*/);
430  }
431 
432  // Re-Initialize costmap downsampler
433  if (reinit_downsampler) {
434  if (_downsample_costmap && _downsampling_factor > 1) {
435  auto node = _node.lock();
436  std::string topic_name = "downsampled_costmap";
437  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
438  _costmap_downsampler->on_configure(
439  node, _global_frame, topic_name, _costmap, _downsampling_factor);
440  _costmap_downsampler->on_activate();
441  }
442  }
443  }
444  result.successful = true;
445  return result;
446 }
447 
448 } // namespace nav2_smac_planner
449 
450 #include "pluginlib/class_list_macros.hpp"
Abstract interface for global planners to adhere to with pluginlib.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:576
bool worldToMapContinuous(double wx, double wy, float &mx, float &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:306
void setCostmap(CostmapT costmap)
Set the current costmap object to use for collision detection.
A costmap grid collision checker.
void setFootprint(const nav2_costmap_2d::Footprint &footprint, const bool &radius, const double &possible_collision_cost)
A constructor for nav2_smac_planner::GridCollisionChecker for use when irregular bin intervals are ap...
void activate() override
Activate lifecycle node.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
void cleanup() override
Cleanup lifecycle node.
void configure(const nav2::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.
void deactivate() override
Deactivate 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.
Parameters for the smoother cost function.
void get(nav2::LifecycleNode::SharedPtr node, const std::string &name)
Get params from ROS parameter.
Definition: types.hpp:75