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