Nav2 Navigation Stack - kilted  kilted
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 rclcpp_lifecycle::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_util::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_util::declare_parameter_if_not_declared(
68  node, name + ".downsample_costmap", rclcpp::ParameterValue(false));
69  node->get_parameter(name + ".downsample_costmap", _downsample_costmap);
70  nav2_util::declare_parameter_if_not_declared(
71  node, name + ".downsampling_factor", rclcpp::ParameterValue(1));
72  node->get_parameter(name + ".downsampling_factor", _downsampling_factor);
73  nav2_util::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_util::declare_parameter_if_not_declared(
78  node, name + ".allow_unknown", rclcpp::ParameterValue(true));
79  node->get_parameter(name + ".allow_unknown", _allow_unknown);
80  nav2_util::declare_parameter_if_not_declared(
81  node, name + ".max_iterations", rclcpp::ParameterValue(1000000));
82  node->get_parameter(name + ".max_iterations", _max_iterations);
83  nav2_util::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_util::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_util::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_util::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_util::declare_parameter_if_not_declared(
99  node, "service_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  if (_downsample_costmap && _downsampling_factor > 1) {
144  std::string topic_name = "downsampled_costmap";
145  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
146  _costmap_downsampler->on_configure(
147  node, _global_frame, topic_name, _costmap, _downsampling_factor);
148  }
149 
150  _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>("unsmoothed_plan", 1);
151 
152  RCLCPP_INFO(
153  _logger, "Configured plugin %s of type SmacPlanner2D with "
154  "tolerance %.2f, maximum iterations %i, "
155  "max on approach iterations %i, and %s.",
156  _name.c_str(), _tolerance, _max_iterations, _max_on_approach_iterations,
157  _allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal");
158 }
159 
161 {
162  RCLCPP_INFO(
163  _logger, "Activating plugin %s of type SmacPlanner2D",
164  _name.c_str());
165  _raw_plan_publisher->on_activate();
166  if (_costmap_downsampler) {
167  _costmap_downsampler->on_activate();
168  }
169  auto node = _node.lock();
170  // Add callback for dynamic parameters
171  _dyn_params_handler = node->add_on_set_parameters_callback(
172  std::bind(&SmacPlanner2D::dynamicParametersCallback, this, _1));
173 }
174 
176 {
177  RCLCPP_INFO(
178  _logger, "Deactivating plugin %s of type SmacPlanner2D",
179  _name.c_str());
180  _raw_plan_publisher->on_deactivate();
181  if (_costmap_downsampler) {
182  _costmap_downsampler->on_deactivate();
183  }
184  // shutdown dyn_param_handler
185  auto node = _node.lock();
186  if (_dyn_params_handler && node) {
187  node->remove_on_set_parameters_callback(_dyn_params_handler.get());
188  }
189  _dyn_params_handler.reset();
190 }
191 
193 {
194  RCLCPP_INFO(
195  _logger, "Cleaning up plugin %s of type SmacPlanner2D",
196  _name.c_str());
197  _a_star.reset();
198  _smoother.reset();
199  if (_costmap_downsampler) {
200  _costmap_downsampler->on_cleanup();
201  _costmap_downsampler.reset();
202  }
203  _raw_plan_publisher.reset();
204 }
205 
206 nav_msgs::msg::Path SmacPlanner2D::createPlan(
207  const geometry_msgs::msg::PoseStamped & start,
208  const geometry_msgs::msg::PoseStamped & goal,
209  std::function<bool()> cancel_checker)
210 {
211  std::lock_guard<std::mutex> lock_reinit(_mutex);
212  steady_clock::time_point a = steady_clock::now();
213 
214  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
215 
216  // Downsample costmap, if required
217  nav2_costmap_2d::Costmap2D * costmap = _costmap;
218  if (_costmap_downsampler) {
219  costmap = _costmap_downsampler->downsample(_downsampling_factor);
220  _collision_checker.setCostmap(costmap);
221  }
222 
223  // Set collision checker and costmap information
224  _a_star->setCollisionChecker(&_collision_checker);
225 
226  // Set starting point
227  float mx_start, my_start, mx_goal, my_goal;
228  if (!costmap->worldToMapContinuous(
229  start.pose.position.x,
230  start.pose.position.y,
231  mx_start,
232  my_start))
233  {
235  "Start Coordinates of(" + std::to_string(start.pose.position.x) + ", " +
236  std::to_string(start.pose.position.y) + ") was outside bounds");
237  }
238  _a_star->setStart(mx_start, my_start, 0);
239 
240  // Set goal point
241  if (!costmap->worldToMapContinuous(
242  goal.pose.position.x,
243  goal.pose.position.y,
244  mx_goal,
245  my_goal))
246  {
248  "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " +
249  std::to_string(goal.pose.position.y) + ") was outside bounds");
250  }
251  _a_star->setGoal(mx_goal, my_goal, 0);
252 
253  // Setup message
254  nav_msgs::msg::Path plan;
255  plan.header.stamp = _clock->now();
256  plan.header.frame_id = _global_frame;
257  geometry_msgs::msg::PoseStamped pose;
258  pose.header = plan.header;
259  pose.pose.position.z = 0.0;
260  pose.pose.orientation.x = 0.0;
261  pose.pose.orientation.y = 0.0;
262  pose.pose.orientation.z = 0.0;
263  pose.pose.orientation.w = 1.0;
264 
265  // Corner case of start and goal being on the same cell
266  if (std::floor(mx_start) == std::floor(mx_goal) && std::floor(my_start) == std::floor(my_goal)) {
267  pose.pose = start.pose;
268  // if we have a different start and goal orientation, set the unique path pose to the goal
269  // orientation, unless use_final_approach_orientation=true where we need it to be the start
270  // orientation to avoid movement from the local planner
271  if (start.pose.orientation != goal.pose.orientation && !_use_final_approach_orientation) {
272  pose.pose.orientation = goal.pose.orientation;
273  }
274  plan.poses.push_back(pose);
275 
276  // Publish raw path for debug
277  if (_raw_plan_publisher->get_subscription_count() > 0) {
278  _raw_plan_publisher->publish(plan);
279  }
280 
281  return plan;
282  }
283 
284  // Compute plan
285  Node2D::CoordinateVector path;
286  int num_iterations = 0;
287  // Note: All exceptions thrown are handled by the planner server and returned to the action
288  if (!_a_star->createPath(
289  path, num_iterations,
290  _tolerance / static_cast<float>(costmap->getResolution()), cancel_checker))
291  {
292  // Note: If the start is blocked only one iteration will occur before failure
293  if (num_iterations == 1) {
294  throw nav2_core::StartOccupied("Start occupied");
295  }
296 
297  if (num_iterations < _a_star->getMaxIterations()) {
298  throw nav2_core::NoValidPathCouldBeFound("no valid path found");
299  } else {
300  throw nav2_core::PlannerTimedOut("exceeded maximum iterations");
301  }
302  }
303 
304  // Convert to world coordinates
305  plan.poses.reserve(path.size());
306  for (int i = path.size() - 1; i >= 0; --i) {
307  pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
308  plan.poses.push_back(pose);
309  }
310 
311  // Publish raw path for debug
312  if (_raw_plan_publisher->get_subscription_count() > 0) {
313  _raw_plan_publisher->publish(plan);
314  }
315 
316  // Find how much time we have left to do smoothing
317  steady_clock::time_point b = steady_clock::now();
318  duration<double> time_span = duration_cast<duration<double>>(b - a);
319  double time_remaining = _max_planning_time - static_cast<double>(time_span.count());
320 
321 #ifdef BENCHMARK_TESTING
322  std::cout << "It took " << time_span.count() * 1000 <<
323  " milliseconds with " << num_iterations << " iterations." << std::endl;
324 #endif
325 
326  // Smooth plan
327  _smoother->smooth(plan, costmap, time_remaining);
328 
329  // If use_final_approach_orientation=true, interpolate the last pose orientation from the
330  // previous pose to set the orientation to the 'final approach' orientation of the robot so
331  // it does not rotate.
332  // And deal with corner case of plan of length 1
333  // If use_final_approach_orientation=false (default), override last pose orientation to match goal
334  size_t plan_size = plan.poses.size();
335  if (_use_final_approach_orientation) {
336  if (plan_size == 1) {
337  plan.poses.back().pose.orientation = start.pose.orientation;
338  } else if (plan_size > 1) {
339  double dx, dy, theta;
340  auto last_pose = plan.poses.back().pose.position;
341  auto approach_pose = plan.poses[plan_size - 2].pose.position;
342  dx = last_pose.x - approach_pose.x;
343  dy = last_pose.y - approach_pose.y;
344  theta = atan2(dy, dx);
345  plan.poses.back().pose.orientation =
346  nav2_util::geometry_utils::orientationAroundZAxis(theta);
347  }
348  } else if (plan_size > 0) {
349  plan.poses.back().pose.orientation = goal.pose.orientation;
350  }
351 
352  return plan;
353 }
354 
355 rcl_interfaces::msg::SetParametersResult
356 SmacPlanner2D::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
357 {
358  rcl_interfaces::msg::SetParametersResult result;
359  std::lock_guard<std::mutex> lock_reinit(_mutex);
360 
361  bool reinit_a_star = false;
362  bool reinit_downsampler = false;
363 
364  for (auto parameter : parameters) {
365  const auto & param_type = parameter.get_type();
366  const auto & param_name = parameter.get_name();
367  if(param_name.find(_name + ".") != 0) {
368  continue;
369  }
370  if (param_type == ParameterType::PARAMETER_DOUBLE) {
371  if (param_name == _name + ".tolerance") {
372  _tolerance = static_cast<float>(parameter.as_double());
373  } else if (param_name == _name + ".cost_travel_multiplier") {
374  reinit_a_star = true;
375  _search_info.cost_penalty = parameter.as_double();
376  } else if (param_name == _name + ".max_planning_time") {
377  reinit_a_star = true;
378  _max_planning_time = parameter.as_double();
379  }
380  } else if (param_type == ParameterType::PARAMETER_BOOL) {
381  if (param_name == _name + ".downsample_costmap") {
382  reinit_downsampler = true;
383  _downsample_costmap = parameter.as_bool();
384  } else if (param_name == _name + ".allow_unknown") {
385  reinit_a_star = true;
386  _allow_unknown = parameter.as_bool();
387  } else if (param_name == _name + ".use_final_approach_orientation") {
388  _use_final_approach_orientation = parameter.as_bool();
389  }
390  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
391  if (param_name == _name + ".downsampling_factor") {
392  reinit_downsampler = true;
393  _downsampling_factor = parameter.as_int();
394  } else if (param_name == _name + ".max_iterations") {
395  reinit_a_star = true;
396  _max_iterations = parameter.as_int();
397  if (_max_iterations <= 0) {
398  RCLCPP_INFO(
399  _logger, "maximum iteration selected as <= 0, "
400  "disabling maximum iterations.");
401  _max_iterations = std::numeric_limits<int>::max();
402  }
403  } else if (param_name == _name + ".max_on_approach_iterations") {
404  reinit_a_star = true;
405  _max_on_approach_iterations = parameter.as_int();
406  if (_max_on_approach_iterations <= 0) {
407  RCLCPP_INFO(
408  _logger, "On approach iteration selected as <= 0, "
409  "disabling tolerance and on approach iterations.");
410  _max_on_approach_iterations = std::numeric_limits<int>::max();
411  }
412  } else if (param_name == _name + ".terminal_checking_interval") {
413  reinit_a_star = true;
414  _terminal_checking_interval = parameter.as_int();
415  }
416  }
417  }
418 
419  // Re-init if needed with mutex lock (to avoid re-init while creating a plan)
420  if (reinit_a_star || reinit_downsampler) {
421  // Re-Initialize A* template
422  if (reinit_a_star) {
423  _a_star = std::make_unique<AStarAlgorithm<Node2D>>(_motion_model, _search_info);
424  _a_star->initialize(
425  _allow_unknown,
426  _max_iterations,
427  _max_on_approach_iterations,
428  _terminal_checking_interval,
429  _max_planning_time,
430  0.0 /*unused for 2D*/,
431  1.0 /*unused for 2D*/);
432  }
433 
434  // Re-Initialize costmap downsampler
435  if (reinit_downsampler) {
436  if (_downsample_costmap && _downsampling_factor > 1) {
437  auto node = _node.lock();
438  std::string topic_name = "downsampled_costmap";
439  _costmap_downsampler = std::make_unique<CostmapDownsampler>();
440  _costmap_downsampler->on_configure(
441  node, _global_frame, topic_name, _costmap, _downsampling_factor);
442  }
443  }
444  }
445  result.successful = true;
446  return result;
447 }
448 
449 } // namespace nav2_smac_planner
450 
451 #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.
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.
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 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(std::shared_ptr< rclcpp_lifecycle::LifecycleNode > node, const std::string &name)
Get params from ROS parameter.
Definition: types.hpp:75