22 #include "nav2_smac_planner/smac_planner_hybrid.hpp"
26 namespace nav2_smac_planner
29 using namespace std::chrono;
30 using rcl_interfaces::msg::ParameterType;
31 using std::placeholders::_1;
35 _collision_checker(nullptr, 1, nullptr),
38 _costmap_downsampler(nullptr)
45 _logger,
"Destroying plugin %s of type SmacPlannerHybrid",
50 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
51 std::string name, std::shared_ptr<tf2_ros::Buffer>,
52 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
55 auto node = parent.lock();
56 _logger = node->get_logger();
57 _clock = node->get_clock();
58 _costmap = costmap_ros->getCostmap();
59 _costmap_ros = costmap_ros;
61 _global_frame = costmap_ros->getGlobalFrameID();
63 RCLCPP_INFO(_logger,
"Configuring %s of type SmacPlannerHybrid", name.c_str());
65 int angle_quantizations;
66 double analytic_expansion_max_length_m;
70 nav2_util::declare_parameter_if_not_declared(
71 node, name +
".downsample_costmap", rclcpp::ParameterValue(
false));
72 node->get_parameter(name +
".downsample_costmap", _downsample_costmap);
73 nav2_util::declare_parameter_if_not_declared(
74 node, name +
".downsampling_factor", rclcpp::ParameterValue(1));
75 node->get_parameter(name +
".downsampling_factor", _downsampling_factor);
77 nav2_util::declare_parameter_if_not_declared(
78 node, name +
".angle_quantization_bins", rclcpp::ParameterValue(72));
79 node->get_parameter(name +
".angle_quantization_bins", angle_quantizations);
80 _angle_bin_size = 2.0 * M_PI / angle_quantizations;
81 _angle_quantizations =
static_cast<unsigned int>(angle_quantizations);
83 nav2_util::declare_parameter_if_not_declared(
84 node, name +
".tolerance", rclcpp::ParameterValue(0.25));
85 _tolerance =
static_cast<float>(node->get_parameter(name +
".tolerance").as_double());
86 nav2_util::declare_parameter_if_not_declared(
87 node, name +
".allow_unknown", rclcpp::ParameterValue(
true));
88 node->get_parameter(name +
".allow_unknown", _allow_unknown);
89 nav2_util::declare_parameter_if_not_declared(
90 node, name +
".max_iterations", rclcpp::ParameterValue(1000000));
91 node->get_parameter(name +
".max_iterations", _max_iterations);
92 nav2_util::declare_parameter_if_not_declared(
93 node, name +
".max_on_approach_iterations", rclcpp::ParameterValue(1000));
94 node->get_parameter(name +
".max_on_approach_iterations", _max_on_approach_iterations);
95 nav2_util::declare_parameter_if_not_declared(
96 node, name +
".smooth_path", rclcpp::ParameterValue(
true));
97 node->get_parameter(name +
".smooth_path", smooth_path);
99 nav2_util::declare_parameter_if_not_declared(
100 node, name +
".minimum_turning_radius", rclcpp::ParameterValue(0.4));
101 node->get_parameter(name +
".minimum_turning_radius", _minimum_turning_radius_global_coords);
102 nav2_util::declare_parameter_if_not_declared(
103 node, name +
".cache_obstacle_heuristic", rclcpp::ParameterValue(
false));
104 node->get_parameter(name +
".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic);
105 nav2_util::declare_parameter_if_not_declared(
106 node, name +
".reverse_penalty", rclcpp::ParameterValue(2.0));
107 node->get_parameter(name +
".reverse_penalty", _search_info.reverse_penalty);
108 nav2_util::declare_parameter_if_not_declared(
109 node, name +
".change_penalty", rclcpp::ParameterValue(0.0));
110 node->get_parameter(name +
".change_penalty", _search_info.change_penalty);
111 nav2_util::declare_parameter_if_not_declared(
112 node, name +
".non_straight_penalty", rclcpp::ParameterValue(1.2));
113 node->get_parameter(name +
".non_straight_penalty", _search_info.non_straight_penalty);
114 nav2_util::declare_parameter_if_not_declared(
115 node, name +
".cost_penalty", rclcpp::ParameterValue(2.0));
116 node->get_parameter(name +
".cost_penalty", _search_info.cost_penalty);
117 nav2_util::declare_parameter_if_not_declared(
118 node, name +
".retrospective_penalty", rclcpp::ParameterValue(0.015));
119 node->get_parameter(name +
".retrospective_penalty", _search_info.retrospective_penalty);
120 nav2_util::declare_parameter_if_not_declared(
121 node, name +
".analytic_expansion_ratio", rclcpp::ParameterValue(3.5));
122 node->get_parameter(name +
".analytic_expansion_ratio", _search_info.analytic_expansion_ratio);
123 nav2_util::declare_parameter_if_not_declared(
124 node, name +
".analytic_expansion_max_length", rclcpp::ParameterValue(3.0));
125 node->get_parameter(name +
".analytic_expansion_max_length", analytic_expansion_max_length_m);
126 _search_info.analytic_expansion_max_length =
129 nav2_util::declare_parameter_if_not_declared(
130 node, name +
".max_planning_time", rclcpp::ParameterValue(5.0));
131 node->get_parameter(name +
".max_planning_time", _max_planning_time);
132 nav2_util::declare_parameter_if_not_declared(
133 node, name +
".lookup_table_size", rclcpp::ParameterValue(20.0));
134 node->get_parameter(name +
".lookup_table_size", _lookup_table_size);
136 nav2_util::declare_parameter_if_not_declared(
137 node, name +
".motion_model_for_search", rclcpp::ParameterValue(std::string(
"DUBIN")));
138 node->get_parameter(name +
".motion_model_for_search", _motion_model_for_search);
139 _motion_model = fromString(_motion_model_for_search);
140 if (_motion_model == MotionModel::UNKNOWN) {
143 "Unable to get MotionModel search type. Given '%s', "
144 "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP, STATE_LATTICE.",
145 _motion_model_for_search.c_str());
148 if (_max_on_approach_iterations <= 0) {
150 _logger,
"On approach iteration selected as <= 0, "
151 "disabling tolerance and on approach iterations.");
152 _max_on_approach_iterations = std::numeric_limits<int>::max();
155 if (_max_iterations <= 0) {
157 _logger,
"maximum iteration selected as <= 0, "
158 "disabling maximum iterations.");
159 _max_iterations = std::numeric_limits<int>::max();
163 if (!_downsample_costmap) {
164 _downsampling_factor = 1;
166 _search_info.minimum_turning_radius =
167 _minimum_turning_radius_global_coords / (_costmap->
getResolution() * _downsampling_factor);
169 static_cast<float>(_lookup_table_size) /
170 static_cast<float>(_costmap->
getResolution() * _downsampling_factor);
173 _lookup_table_dim =
static_cast<float>(
static_cast<int>(_lookup_table_dim));
176 if (
static_cast<int>(_lookup_table_dim) % 2 == 0) {
179 "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
181 _lookup_table_dim += 1.0;
187 _costmap_ros->getRobotFootprint(),
188 _costmap_ros->getUseRadius(),
189 findCircumscribedCost(_costmap_ros));
192 _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
196 _max_on_approach_iterations,
199 _angle_quantizations);
204 params.
get(node, name);
205 _smoother = std::make_unique<Smoother>(params);
206 _smoother->initialize(_minimum_turning_radius_global_coords);
210 if (_downsample_costmap && _downsampling_factor > 1) {
211 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
212 std::string topic_name =
"downsampled_costmap";
213 _costmap_downsampler->on_configure(
214 node, _global_frame, topic_name, _costmap, _downsampling_factor);
217 _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>(
"unsmoothed_plan", 1);
220 _logger,
"Configured plugin %s of type SmacPlannerHybrid with "
221 "maximum iterations %i, max on approach iterations %i, and %s. Tolerance %.2f."
222 "Using motion model: %s.",
223 _name.c_str(), _max_iterations, _max_on_approach_iterations,
224 _allow_unknown ?
"allowing unknown traversal" :
"not allowing unknown traversal",
225 _tolerance, toString(_motion_model).c_str());
231 _logger,
"Activating plugin %s of type SmacPlannerHybrid",
233 _raw_plan_publisher->on_activate();
234 if (_costmap_downsampler) {
235 _costmap_downsampler->on_activate();
237 auto node = _node.lock();
239 _dyn_params_handler = node->add_on_set_parameters_callback(
246 _logger,
"Deactivating plugin %s of type SmacPlannerHybrid",
248 _raw_plan_publisher->on_deactivate();
249 if (_costmap_downsampler) {
250 _costmap_downsampler->on_deactivate();
252 _dyn_params_handler.reset();
258 _logger,
"Cleaning up plugin %s of type SmacPlannerHybrid",
262 if (_costmap_downsampler) {
263 _costmap_downsampler->on_cleanup();
264 _costmap_downsampler.reset();
266 _raw_plan_publisher.reset();
270 const geometry_msgs::msg::PoseStamped & start,
271 const geometry_msgs::msg::PoseStamped & goal)
273 std::lock_guard<std::mutex> lock_reinit(_mutex);
274 steady_clock::time_point a = steady_clock::now();
276 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
280 if (_costmap_downsampler) {
281 costmap = _costmap_downsampler->downsample(_downsampling_factor);
287 _costmap_ros->getRobotFootprint(),
288 _costmap_ros->getUseRadius(),
289 findCircumscribedCost(_costmap_ros));
290 _a_star->setCollisionChecker(&_collision_checker);
294 if (!costmap->
worldToMap(start.pose.position.x, start.pose.position.y, mx, my)) {
295 throw std::runtime_error(
"Start pose is out of costmap!");
298 double orientation_bin = std::round(tf2::getYaw(start.pose.orientation) / _angle_bin_size);
299 while (orientation_bin < 0.0) {
300 orientation_bin +=
static_cast<float>(_angle_quantizations);
303 if (orientation_bin >=
static_cast<float>(_angle_quantizations)) {
304 orientation_bin -=
static_cast<float>(_angle_quantizations);
306 _a_star->setStart(mx, my,
static_cast<unsigned int>(orientation_bin));
309 if (!costmap->
worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my)) {
310 throw std::runtime_error(
"Goal pose is out of costmap!");
312 orientation_bin = std::round(tf2::getYaw(goal.pose.orientation) / _angle_bin_size);
313 while (orientation_bin < 0.0) {
314 orientation_bin +=
static_cast<float>(_angle_quantizations);
317 if (orientation_bin >=
static_cast<float>(_angle_quantizations)) {
318 orientation_bin -=
static_cast<float>(_angle_quantizations);
320 _a_star->setGoal(mx, my,
static_cast<unsigned int>(orientation_bin));
323 nav_msgs::msg::Path plan;
324 plan.header.stamp = _clock->now();
325 plan.header.frame_id = _global_frame;
326 geometry_msgs::msg::PoseStamped pose;
327 pose.header = plan.header;
328 pose.pose.position.z = 0.0;
329 pose.pose.orientation.x = 0.0;
330 pose.pose.orientation.y = 0.0;
331 pose.pose.orientation.z = 0.0;
332 pose.pose.orientation.w = 1.0;
335 NodeHybrid::CoordinateVector path;
336 int num_iterations = 0;
339 if (!_a_star->createPath(
340 path, num_iterations, _tolerance /
static_cast<float>(costmap->
getResolution())))
342 if (num_iterations < _a_star->getMaxIterations()) {
343 error = std::string(
"no valid path found");
345 error = std::string(
"exceeded maximum iterations");
348 }
catch (
const std::runtime_error & e) {
349 error =
"invalid use: ";
353 if (!error.empty()) {
356 "%s: failed to create plan, %s.",
357 _name.c_str(), error.c_str());
362 plan.poses.reserve(path.size());
363 for (
int i = path.size() - 1; i >= 0; --i) {
364 pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
365 pose.pose.orientation = getWorldOrientation(path[i].theta);
366 plan.poses.push_back(pose);
370 if (_raw_plan_publisher->get_subscription_count() > 0) {
371 _raw_plan_publisher->publish(plan);
375 steady_clock::time_point b = steady_clock::now();
376 duration<double> time_span = duration_cast<duration<double>>(b - a);
377 double time_remaining = _max_planning_time -
static_cast<double>(time_span.count());
379 #ifdef BENCHMARK_TESTING
380 std::cout <<
"It took " << time_span.count() * 1000 <<
381 " milliseconds with " << num_iterations <<
" iterations." << std::endl;
385 if (_smoother && num_iterations > 1) {
386 _smoother->smooth(plan, costmap, time_remaining);
389 #ifdef BENCHMARK_TESTING
390 steady_clock::time_point c = steady_clock::now();
391 duration<double> time_span2 = duration_cast<duration<double>>(c - b);
392 std::cout <<
"It took " << time_span2.count() * 1000 <<
393 " milliseconds to smooth path." << std::endl;
399 rcl_interfaces::msg::SetParametersResult
402 rcl_interfaces::msg::SetParametersResult result;
403 std::lock_guard<std::mutex> lock_reinit(_mutex);
405 bool reinit_collision_checker =
false;
406 bool reinit_a_star =
false;
407 bool reinit_downsampler =
false;
408 bool reinit_smoother =
false;
410 for (
auto parameter : parameters) {
411 const auto & type = parameter.get_type();
412 const auto & name = parameter.get_name();
414 if (type == ParameterType::PARAMETER_DOUBLE) {
415 if (name == _name +
".max_planning_time") {
416 reinit_a_star =
true;
417 _max_planning_time = parameter.as_double();
418 }
else if (name == _name +
".tolerance") {
419 _tolerance =
static_cast<float>(parameter.as_double());
420 }
else if (name == _name +
".lookup_table_size") {
421 reinit_a_star =
true;
422 _lookup_table_size = parameter.as_double();
423 }
else if (name == _name +
".minimum_turning_radius") {
424 reinit_a_star =
true;
426 reinit_smoother =
true;
428 _minimum_turning_radius_global_coords =
static_cast<float>(parameter.as_double());
429 }
else if (name == _name +
".reverse_penalty") {
430 reinit_a_star =
true;
431 _search_info.reverse_penalty =
static_cast<float>(parameter.as_double());
432 }
else if (name == _name +
".change_penalty") {
433 reinit_a_star =
true;
434 _search_info.change_penalty =
static_cast<float>(parameter.as_double());
435 }
else if (name == _name +
".non_straight_penalty") {
436 reinit_a_star =
true;
437 _search_info.non_straight_penalty =
static_cast<float>(parameter.as_double());
438 }
else if (name == _name +
".cost_penalty") {
439 reinit_a_star =
true;
440 _search_info.cost_penalty =
static_cast<float>(parameter.as_double());
441 }
else if (name == _name +
".analytic_expansion_ratio") {
442 reinit_a_star =
true;
443 _search_info.analytic_expansion_ratio =
static_cast<float>(parameter.as_double());
444 }
else if (name == _name +
".analytic_expansion_max_length") {
445 reinit_a_star =
true;
446 _search_info.analytic_expansion_max_length =
447 static_cast<float>(parameter.as_double()) / _costmap->
getResolution();
449 }
else if (type == ParameterType::PARAMETER_BOOL) {
450 if (name == _name +
".downsample_costmap") {
451 reinit_downsampler =
true;
452 _downsample_costmap = parameter.as_bool();
453 }
else if (name == _name +
".allow_unknown") {
454 reinit_a_star =
true;
455 _allow_unknown = parameter.as_bool();
456 }
else if (name == _name +
".cache_obstacle_heuristic") {
457 reinit_a_star =
true;
458 _search_info.cache_obstacle_heuristic = parameter.as_bool();
459 }
else if (name == _name +
".smooth_path") {
460 if (parameter.as_bool()) {
461 reinit_smoother =
true;
466 }
else if (type == ParameterType::PARAMETER_INTEGER) {
467 if (name == _name +
".downsampling_factor") {
468 reinit_a_star =
true;
469 reinit_downsampler =
true;
470 _downsampling_factor = parameter.as_int();
471 }
else if (name == _name +
".max_iterations") {
472 reinit_a_star =
true;
473 _max_iterations = parameter.as_int();
474 if (_max_iterations <= 0) {
476 _logger,
"maximum iteration selected as <= 0, "
477 "disabling maximum iterations.");
478 _max_iterations = std::numeric_limits<int>::max();
480 }
else if (name == _name +
".max_on_approach_iterations") {
481 reinit_a_star =
true;
482 _max_on_approach_iterations = parameter.as_int();
483 if (_max_on_approach_iterations <= 0) {
485 _logger,
"On approach iteration selected as <= 0, "
486 "disabling tolerance and on approach iterations.");
487 _max_on_approach_iterations = std::numeric_limits<int>::max();
489 }
else if (name == _name +
".angle_quantization_bins") {
490 reinit_collision_checker =
true;
491 reinit_a_star =
true;
492 int angle_quantizations = parameter.as_int();
493 _angle_bin_size = 2.0 * M_PI / angle_quantizations;
494 _angle_quantizations =
static_cast<unsigned int>(angle_quantizations);
496 }
else if (type == ParameterType::PARAMETER_STRING) {
497 if (name == _name +
".motion_model_for_search") {
498 reinit_a_star =
true;
499 _motion_model = fromString(parameter.as_string());
500 if (_motion_model == MotionModel::UNKNOWN) {
503 "Unable to get MotionModel search type. Given '%s', "
504 "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP.",
505 _motion_model_for_search.c_str());
512 if (reinit_a_star || reinit_downsampler || reinit_collision_checker || reinit_smoother) {
514 if (!_downsample_costmap) {
515 _downsampling_factor = 1;
517 _search_info.minimum_turning_radius =
518 _minimum_turning_radius_global_coords / (_costmap->
getResolution() * _downsampling_factor);
520 static_cast<float>(_lookup_table_size) /
521 static_cast<float>(_costmap->
getResolution() * _downsampling_factor);
524 _lookup_table_dim =
static_cast<float>(
static_cast<int>(_lookup_table_dim));
527 if (
static_cast<int>(_lookup_table_dim) % 2 == 0) {
530 "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
532 _lookup_table_dim += 1.0;
535 auto node = _node.lock();
539 _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
543 _max_on_approach_iterations,
546 _angle_quantizations);
550 if (reinit_downsampler) {
551 if (_downsample_costmap && _downsampling_factor > 1) {
552 std::string topic_name =
"downsampled_costmap";
553 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
554 _costmap_downsampler->on_configure(
555 node, _global_frame, topic_name, _costmap, _downsampling_factor);
560 if (reinit_collision_checker) {
563 _costmap_ros->getRobotFootprint(),
564 _costmap_ros->getUseRadius(),
565 findCircumscribedCost(_costmap_ros));
569 if (reinit_smoother) {
571 params.
get(node, _name);
572 _smoother = std::make_unique<Smoother>(params);
573 _smoother->initialize(_minimum_turning_radius_global_coords);
576 result.successful =
true;
582 #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".
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
double getResolution() const
Accessor for the resolution of the costmap.
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...
SmacPlannerHybrid()
constructor
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.
void activate() override
Activate lifecycle node.
void cleanup() override
Cleanup lifecycle node.
void deactivate() override
Deactivate lifecycle node.
~SmacPlannerHybrid()
destructor
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
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.