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