23 #include "nav2_smac_planner/smac_planner_hybrid.hpp"
27 namespace nav2_smac_planner
30 using namespace std::chrono;
31 using rcl_interfaces::msg::ParameterType;
32 using std::placeholders::_1;
36 _collision_checker(nullptr, 1, nullptr),
39 _costmap_ros(nullptr),
40 _costmap_downsampler(nullptr)
47 _logger,
"Destroying plugin %s of type SmacPlannerHybrid",
52 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
53 std::string name, std::shared_ptr<tf2_ros::Buffer>,
54 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
57 auto node = parent.lock();
58 _logger = node->get_logger();
59 _clock = node->get_clock();
60 _costmap = costmap_ros->getCostmap();
61 _costmap_ros = costmap_ros;
63 _global_frame = costmap_ros->getGlobalFrameID();
65 RCLCPP_INFO(_logger,
"Configuring %s of type SmacPlannerHybrid", name.c_str());
67 int angle_quantizations;
68 double analytic_expansion_max_length_m;
72 nav2_util::declare_parameter_if_not_declared(
73 node, name +
".downsample_costmap", rclcpp::ParameterValue(
false));
74 node->get_parameter(name +
".downsample_costmap", _downsample_costmap);
75 nav2_util::declare_parameter_if_not_declared(
76 node, name +
".downsampling_factor", rclcpp::ParameterValue(1));
77 node->get_parameter(name +
".downsampling_factor", _downsampling_factor);
79 nav2_util::declare_parameter_if_not_declared(
80 node, name +
".angle_quantization_bins", rclcpp::ParameterValue(72));
81 node->get_parameter(name +
".angle_quantization_bins", angle_quantizations);
82 _angle_bin_size = 2.0 * M_PI / angle_quantizations;
83 _angle_quantizations =
static_cast<unsigned int>(angle_quantizations);
85 nav2_util::declare_parameter_if_not_declared(
86 node, name +
".tolerance", rclcpp::ParameterValue(0.25));
87 _tolerance =
static_cast<float>(node->get_parameter(name +
".tolerance").as_double());
88 nav2_util::declare_parameter_if_not_declared(
89 node, name +
".allow_unknown", rclcpp::ParameterValue(
true));
90 node->get_parameter(name +
".allow_unknown", _allow_unknown);
91 nav2_util::declare_parameter_if_not_declared(
92 node, name +
".max_iterations", rclcpp::ParameterValue(1000000));
93 node->get_parameter(name +
".max_iterations", _max_iterations);
94 nav2_util::declare_parameter_if_not_declared(
95 node, name +
".max_on_approach_iterations", rclcpp::ParameterValue(1000));
96 node->get_parameter(name +
".max_on_approach_iterations", _max_on_approach_iterations);
97 nav2_util::declare_parameter_if_not_declared(
98 node, name +
".terminal_checking_interval", rclcpp::ParameterValue(5000));
99 node->get_parameter(name +
".terminal_checking_interval", _terminal_checking_interval);
100 nav2_util::declare_parameter_if_not_declared(
101 node, name +
".smooth_path", rclcpp::ParameterValue(
true));
102 node->get_parameter(name +
".smooth_path", smooth_path);
104 nav2_util::declare_parameter_if_not_declared(
105 node, name +
".minimum_turning_radius", rclcpp::ParameterValue(0.4));
106 node->get_parameter(name +
".minimum_turning_radius", _minimum_turning_radius_global_coords);
107 nav2_util::declare_parameter_if_not_declared(
108 node, name +
".allow_primitive_interpolation", rclcpp::ParameterValue(
false));
110 name +
".allow_primitive_interpolation", _search_info.allow_primitive_interpolation);
111 nav2_util::declare_parameter_if_not_declared(
112 node, name +
".cache_obstacle_heuristic", rclcpp::ParameterValue(
false));
113 node->get_parameter(name +
".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic);
114 nav2_util::declare_parameter_if_not_declared(
115 node, name +
".reverse_penalty", rclcpp::ParameterValue(2.0));
116 node->get_parameter(name +
".reverse_penalty", _search_info.reverse_penalty);
117 nav2_util::declare_parameter_if_not_declared(
118 node, name +
".change_penalty", rclcpp::ParameterValue(0.0));
119 node->get_parameter(name +
".change_penalty", _search_info.change_penalty);
120 nav2_util::declare_parameter_if_not_declared(
121 node, name +
".non_straight_penalty", rclcpp::ParameterValue(1.2));
122 node->get_parameter(name +
".non_straight_penalty", _search_info.non_straight_penalty);
123 nav2_util::declare_parameter_if_not_declared(
124 node, name +
".cost_penalty", rclcpp::ParameterValue(2.0));
125 node->get_parameter(name +
".cost_penalty", _search_info.cost_penalty);
126 nav2_util::declare_parameter_if_not_declared(
127 node, name +
".retrospective_penalty", rclcpp::ParameterValue(0.015));
128 node->get_parameter(name +
".retrospective_penalty", _search_info.retrospective_penalty);
129 nav2_util::declare_parameter_if_not_declared(
130 node, name +
".analytic_expansion_ratio", rclcpp::ParameterValue(3.5));
131 node->get_parameter(name +
".analytic_expansion_ratio", _search_info.analytic_expansion_ratio);
132 nav2_util::declare_parameter_if_not_declared(
133 node, name +
".analytic_expansion_max_cost", rclcpp::ParameterValue(200.0));
135 name +
".analytic_expansion_max_cost", _search_info.analytic_expansion_max_cost);
136 nav2_util::declare_parameter_if_not_declared(
137 node, name +
".analytic_expansion_max_cost_override", rclcpp::ParameterValue(
false));
139 name +
".analytic_expansion_max_cost_override",
140 _search_info.analytic_expansion_max_cost_override);
141 nav2_util::declare_parameter_if_not_declared(
142 node, name +
".use_quadratic_cost_penalty", rclcpp::ParameterValue(
false));
144 name +
".use_quadratic_cost_penalty", _search_info.use_quadratic_cost_penalty);
145 nav2_util::declare_parameter_if_not_declared(
146 node, name +
".downsample_obstacle_heuristic", rclcpp::ParameterValue(
true));
148 name +
".downsample_obstacle_heuristic", _search_info.downsample_obstacle_heuristic);
150 nav2_util::declare_parameter_if_not_declared(
151 node, name +
".analytic_expansion_max_length", rclcpp::ParameterValue(3.0));
152 node->get_parameter(name +
".analytic_expansion_max_length", analytic_expansion_max_length_m);
153 _search_info.analytic_expansion_max_length =
156 nav2_util::declare_parameter_if_not_declared(
157 node, name +
".max_planning_time", rclcpp::ParameterValue(5.0));
158 node->get_parameter(name +
".max_planning_time", _max_planning_time);
159 nav2_util::declare_parameter_if_not_declared(
160 node, name +
".lookup_table_size", rclcpp::ParameterValue(20.0));
161 node->get_parameter(name +
".lookup_table_size", _lookup_table_size);
163 nav2_util::declare_parameter_if_not_declared(
164 node, name +
".debug_visualizations", rclcpp::ParameterValue(
false));
165 node->get_parameter(name +
".debug_visualizations", _debug_visualizations);
167 nav2_util::declare_parameter_if_not_declared(
168 node, name +
".motion_model_for_search", rclcpp::ParameterValue(std::string(
"DUBIN")));
169 node->get_parameter(name +
".motion_model_for_search", _motion_model_for_search);
170 _motion_model = fromString(_motion_model_for_search);
171 if (_motion_model == MotionModel::UNKNOWN) {
174 "Unable to get MotionModel search type. Given '%s', "
175 "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP, STATE_LATTICE.",
176 _motion_model_for_search.c_str());
179 if (_max_on_approach_iterations <= 0) {
181 _logger,
"On approach iteration selected as <= 0, "
182 "disabling tolerance and on approach iterations.");
183 _max_on_approach_iterations = std::numeric_limits<int>::max();
186 if (_max_iterations <= 0) {
188 _logger,
"maximum iteration selected as <= 0, "
189 "disabling maximum iterations.");
190 _max_iterations = std::numeric_limits<int>::max();
193 if (_minimum_turning_radius_global_coords < _costmap->getResolution() * _downsampling_factor) {
195 _logger,
"Min turning radius cannot be less than the search grid cell resolution!");
196 _minimum_turning_radius_global_coords = _costmap->
getResolution() * _downsampling_factor;
200 if (!_downsample_costmap) {
201 _downsampling_factor = 1;
203 _search_info.minimum_turning_radius =
204 _minimum_turning_radius_global_coords / (_costmap->
getResolution() * _downsampling_factor);
206 static_cast<float>(_lookup_table_size) /
207 static_cast<float>(_costmap->
getResolution() * _downsampling_factor);
210 _lookup_table_dim =
static_cast<float>(
static_cast<int>(_lookup_table_dim));
213 if (
static_cast<int>(_lookup_table_dim) % 2 == 0) {
216 "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
218 _lookup_table_dim += 1.0;
224 _costmap_ros->getRobotFootprint(),
225 _costmap_ros->getUseRadius(),
226 findCircumscribedCost(_costmap_ros));
229 _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
233 _max_on_approach_iterations,
234 _terminal_checking_interval,
237 _angle_quantizations);
242 params.
get(node, name);
243 _smoother = std::make_unique<Smoother>(params);
244 _smoother->initialize(_minimum_turning_radius_global_coords);
248 if (_downsample_costmap && _downsampling_factor > 1) {
249 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
250 std::string topic_name =
"downsampled_costmap";
251 _costmap_downsampler->on_configure(
252 node, _global_frame, topic_name, _costmap, _downsampling_factor);
255 _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>(
"unsmoothed_plan", 1);
257 if (_debug_visualizations) {
258 _expansions_publisher = node->create_publisher<geometry_msgs::msg::PoseArray>(
"expansions", 1);
259 _planned_footprints_publisher = node->create_publisher<visualization_msgs::msg::MarkerArray>(
260 "planned_footprints", 1);
261 _smoothed_footprints_publisher =
262 node->create_publisher<visualization_msgs::msg::MarkerArray>(
263 "smoothed_footprints", 1);
267 _logger,
"Configured plugin %s of type SmacPlannerHybrid with "
268 "maximum iterations %i, max on approach iterations %i, and %s. Tolerance %.2f."
269 "Using motion model: %s.",
270 _name.c_str(), _max_iterations, _max_on_approach_iterations,
271 _allow_unknown ?
"allowing unknown traversal" :
"not allowing unknown traversal",
272 _tolerance, toString(_motion_model).c_str());
278 _logger,
"Activating plugin %s of type SmacPlannerHybrid",
280 _raw_plan_publisher->on_activate();
281 if (_debug_visualizations) {
282 _expansions_publisher->on_activate();
283 _planned_footprints_publisher->on_activate();
284 _smoothed_footprints_publisher->on_activate();
286 if (_costmap_downsampler) {
287 _costmap_downsampler->on_activate();
289 auto node = _node.lock();
291 _dyn_params_handler = node->add_on_set_parameters_callback(
295 auto resolution_remote_cb = [
this](
const rclcpp::Parameter & p) {
296 auto node = _node.lock();
298 {rclcpp::Parameter(
"resolution", rclcpp::ParameterValue(p.as_double()))});
300 _remote_param_subscriber = std::make_shared<rclcpp::ParameterEventHandler>(_node.lock());
301 _remote_resolution_handler = _remote_param_subscriber->add_parameter_callback(
302 "resolution", resolution_remote_cb,
"global_costmap/global_costmap");
308 _logger,
"Deactivating plugin %s of type SmacPlannerHybrid",
310 _raw_plan_publisher->on_deactivate();
311 if (_debug_visualizations) {
312 _expansions_publisher->on_deactivate();
313 _planned_footprints_publisher->on_deactivate();
314 _smoothed_footprints_publisher->on_deactivate();
316 if (_costmap_downsampler) {
317 _costmap_downsampler->on_deactivate();
320 auto node = _node.lock();
321 if (_dyn_params_handler && node) {
322 node->remove_on_set_parameters_callback(_dyn_params_handler.get());
324 _dyn_params_handler.reset();
330 _logger,
"Cleaning up plugin %s of type SmacPlannerHybrid",
335 if (_costmap_downsampler) {
336 _costmap_downsampler->on_cleanup();
337 _costmap_downsampler.reset();
339 _raw_plan_publisher.reset();
340 if (_debug_visualizations) {
341 _expansions_publisher.reset();
342 _planned_footprints_publisher.reset();
343 _smoothed_footprints_publisher.reset();
348 const geometry_msgs::msg::PoseStamped & start,
349 const geometry_msgs::msg::PoseStamped & goal,
350 std::function<
bool()> cancel_checker)
352 std::lock_guard<std::mutex> lock_reinit(_mutex);
353 steady_clock::time_point a = steady_clock::now();
355 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
359 if (_costmap_downsampler) {
360 costmap = _costmap_downsampler->downsample(_downsampling_factor);
366 _costmap_ros->getRobotFootprint(),
367 _costmap_ros->getUseRadius(),
368 findCircumscribedCost(_costmap_ros));
369 _a_star->setCollisionChecker(&_collision_checker);
372 float mx_start, my_start, mx_goal, my_goal;
374 start.pose.position.x,
375 start.pose.position.y,
380 "Start Coordinates of(" + std::to_string(start.pose.position.x) +
", " +
381 std::to_string(start.pose.position.y) +
") was outside bounds");
384 double orientation_bin = std::round(tf2::getYaw(start.pose.orientation) / _angle_bin_size);
385 while (orientation_bin < 0.0) {
386 orientation_bin +=
static_cast<float>(_angle_quantizations);
389 if (orientation_bin >=
static_cast<float>(_angle_quantizations)) {
390 orientation_bin -=
static_cast<float>(_angle_quantizations);
392 _a_star->setStart(mx_start, my_start,
static_cast<unsigned int>(orientation_bin));
396 goal.pose.position.x,
397 goal.pose.position.y,
402 "Goal Coordinates of(" + std::to_string(goal.pose.position.x) +
", " +
403 std::to_string(goal.pose.position.y) +
") was outside bounds");
405 orientation_bin = std::round(tf2::getYaw(goal.pose.orientation) / _angle_bin_size);
406 while (orientation_bin < 0.0) {
407 orientation_bin +=
static_cast<float>(_angle_quantizations);
410 if (orientation_bin >=
static_cast<float>(_angle_quantizations)) {
411 orientation_bin -=
static_cast<float>(_angle_quantizations);
413 _a_star->setGoal(mx_goal, my_goal,
static_cast<unsigned int>(orientation_bin));
416 nav_msgs::msg::Path plan;
417 plan.header.stamp = _clock->now();
418 plan.header.frame_id = _global_frame;
419 geometry_msgs::msg::PoseStamped pose;
420 pose.header = plan.header;
421 pose.pose.position.z = 0.0;
422 pose.pose.orientation.x = 0.0;
423 pose.pose.orientation.y = 0.0;
424 pose.pose.orientation.z = 0.0;
425 pose.pose.orientation.w = 1.0;
428 if (std::floor(mx_start) == std::floor(mx_goal) &&
429 std::floor(my_start) == std::floor(my_goal))
431 pose.pose = start.pose;
432 pose.pose.orientation = goal.pose.orientation;
433 plan.poses.push_back(pose);
436 if (_raw_plan_publisher->get_subscription_count() > 0) {
437 _raw_plan_publisher->publish(plan);
444 NodeHybrid::CoordinateVector path;
445 int num_iterations = 0;
447 std::unique_ptr<std::vector<std::tuple<float, float, float>>> expansions =
nullptr;
448 if (_debug_visualizations) {
449 expansions = std::make_unique<std::vector<std::tuple<float, float, float>>>();
452 if (!_a_star->createPath(
453 path, num_iterations,
454 _tolerance /
static_cast<float>(costmap->
getResolution()), cancel_checker, expansions.get()))
456 if (_debug_visualizations) {
457 geometry_msgs::msg::PoseArray msg;
458 geometry_msgs::msg::Pose msg_pose;
459 msg.header.stamp = _clock->now();
460 msg.header.frame_id = _global_frame;
461 for (
auto & e : *expansions) {
462 msg_pose.position.x = std::get<0>(e);
463 msg_pose.position.y = std::get<1>(e);
464 msg_pose.orientation = getWorldOrientation(std::get<2>(e));
465 msg.poses.push_back(msg_pose);
467 _expansions_publisher->publish(msg);
471 if (num_iterations == 1) {
475 if (num_iterations < _a_star->getMaxIterations()) {
483 plan.poses.reserve(path.size());
484 for (
int i = path.size() - 1; i >= 0; --i) {
485 pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
486 pose.pose.orientation = getWorldOrientation(path[i].theta);
487 plan.poses.push_back(pose);
491 if (_raw_plan_publisher->get_subscription_count() > 0) {
492 _raw_plan_publisher->publish(plan);
495 if (_debug_visualizations) {
497 auto now = _clock->now();
498 geometry_msgs::msg::PoseArray msg;
499 geometry_msgs::msg::Pose msg_pose;
500 msg.header.stamp = now;
501 msg.header.frame_id = _global_frame;
502 for (
auto & e : *expansions) {
503 msg_pose.position.x = std::get<0>(e);
504 msg_pose.position.y = std::get<1>(e);
505 msg_pose.orientation = getWorldOrientation(std::get<2>(e));
506 msg.poses.push_back(msg_pose);
508 _expansions_publisher->publish(msg);
510 if (_planned_footprints_publisher->get_subscription_count() > 0) {
512 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
513 visualization_msgs::msg::Marker clear_all_marker;
514 clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
515 marker_array->markers.push_back(clear_all_marker);
516 _planned_footprints_publisher->publish(std::move(marker_array));
519 marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
520 for (
size_t i = 0; i < plan.poses.size(); i++) {
521 const std::vector<geometry_msgs::msg::Point> edge =
522 transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
523 marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
525 _planned_footprints_publisher->publish(std::move(marker_array));
530 steady_clock::time_point b = steady_clock::now();
531 duration<double> time_span = duration_cast<duration<double>>(b - a);
532 double time_remaining = _max_planning_time -
static_cast<double>(time_span.count());
534 #ifdef BENCHMARK_TESTING
535 std::cout <<
"It took " << time_span.count() * 1000 <<
536 " milliseconds with " << num_iterations <<
" iterations." << std::endl;
540 if (_smoother && num_iterations > 1) {
541 _smoother->smooth(plan, costmap, time_remaining);
544 #ifdef BENCHMARK_TESTING
545 steady_clock::time_point c = steady_clock::now();
546 duration<double> time_span2 = duration_cast<duration<double>>(c - b);
547 std::cout <<
"It took " << time_span2.count() * 1000 <<
548 " milliseconds to smooth path." << std::endl;
551 if (_debug_visualizations) {
552 if (_smoothed_footprints_publisher->get_subscription_count() > 0) {
554 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
555 visualization_msgs::msg::Marker clear_all_marker;
556 clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
557 marker_array->markers.push_back(clear_all_marker);
558 _smoothed_footprints_publisher->publish(std::move(marker_array));
561 marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
562 auto now = _clock->now();
563 for (
size_t i = 0; i < plan.poses.size(); i++) {
564 const std::vector<geometry_msgs::msg::Point> edge =
565 transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
566 marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
568 _smoothed_footprints_publisher->publish(std::move(marker_array));
575 rcl_interfaces::msg::SetParametersResult
578 rcl_interfaces::msg::SetParametersResult result;
579 std::lock_guard<std::mutex> lock_reinit(_mutex);
581 bool reinit_collision_checker =
false;
582 bool reinit_a_star =
false;
583 bool reinit_downsampler =
false;
584 bool reinit_smoother =
false;
586 for (
auto parameter : parameters) {
587 const auto & type = parameter.get_type();
588 const auto & name = parameter.get_name();
590 if (type == ParameterType::PARAMETER_DOUBLE) {
591 if (name == _name +
".max_planning_time") {
592 reinit_a_star =
true;
593 _max_planning_time = parameter.as_double();
594 }
else if (name == _name +
".tolerance") {
595 _tolerance =
static_cast<float>(parameter.as_double());
596 }
else if (name == _name +
".lookup_table_size") {
597 reinit_a_star =
true;
598 _lookup_table_size = parameter.as_double();
599 }
else if (name == _name +
".minimum_turning_radius") {
600 reinit_a_star =
true;
602 reinit_smoother =
true;
605 if (parameter.as_double() < _costmap->
getResolution() * _downsampling_factor) {
607 _logger,
"Min turning radius cannot be less than the search grid cell resolution!");
608 result.successful =
false;
611 _minimum_turning_radius_global_coords =
static_cast<float>(parameter.as_double());
612 }
else if (name == _name +
".reverse_penalty") {
613 reinit_a_star =
true;
614 _search_info.reverse_penalty =
static_cast<float>(parameter.as_double());
615 }
else if (name == _name +
".change_penalty") {
616 reinit_a_star =
true;
617 _search_info.change_penalty =
static_cast<float>(parameter.as_double());
618 }
else if (name == _name +
".non_straight_penalty") {
619 reinit_a_star =
true;
620 _search_info.non_straight_penalty =
static_cast<float>(parameter.as_double());
621 }
else if (name == _name +
".cost_penalty") {
622 reinit_a_star =
true;
623 _search_info.cost_penalty =
static_cast<float>(parameter.as_double());
624 }
else if (name == _name +
".analytic_expansion_ratio") {
625 reinit_a_star =
true;
626 _search_info.analytic_expansion_ratio =
static_cast<float>(parameter.as_double());
627 }
else if (name == _name +
".analytic_expansion_max_length") {
628 reinit_a_star =
true;
629 _search_info.analytic_expansion_max_length =
630 static_cast<float>(parameter.as_double()) / _costmap->
getResolution();
631 }
else if (name == _name +
".analytic_expansion_max_cost") {
632 reinit_a_star =
true;
633 _search_info.analytic_expansion_max_cost =
static_cast<float>(parameter.as_double());
634 }
else if (name ==
"resolution") {
637 RCLCPP_INFO(_logger,
"Costmap resolution changed. Reinitializing SmacPlannerHybrid.");
638 reinit_collision_checker =
true;
639 reinit_a_star =
true;
640 reinit_downsampler =
true;
641 reinit_smoother =
true;
643 }
else if (type == ParameterType::PARAMETER_BOOL) {
644 if (name == _name +
".downsample_costmap") {
645 reinit_downsampler =
true;
646 _downsample_costmap = parameter.as_bool();
647 }
else if (name == _name +
".allow_unknown") {
648 reinit_a_star =
true;
649 _allow_unknown = parameter.as_bool();
650 }
else if (name == _name +
".cache_obstacle_heuristic") {
651 reinit_a_star =
true;
652 _search_info.cache_obstacle_heuristic = parameter.as_bool();
653 }
else if (name == _name +
".allow_primitive_interpolation") {
654 _search_info.allow_primitive_interpolation = parameter.as_bool();
655 reinit_a_star =
true;
656 }
else if (name == _name +
".smooth_path") {
657 if (parameter.as_bool()) {
658 reinit_smoother =
true;
662 }
else if (name == _name +
".analytic_expansion_max_cost_override") {
663 _search_info.analytic_expansion_max_cost_override = parameter.as_bool();
664 reinit_a_star =
true;
666 }
else if (type == ParameterType::PARAMETER_INTEGER) {
667 if (name == _name +
".downsampling_factor") {
668 reinit_a_star =
true;
669 reinit_downsampler =
true;
670 _downsampling_factor = parameter.as_int();
671 }
else if (name == _name +
".max_iterations") {
672 reinit_a_star =
true;
673 _max_iterations = parameter.as_int();
674 if (_max_iterations <= 0) {
676 _logger,
"maximum iteration selected as <= 0, "
677 "disabling maximum iterations.");
678 _max_iterations = std::numeric_limits<int>::max();
680 }
else if (name == _name +
".max_on_approach_iterations") {
681 reinit_a_star =
true;
682 _max_on_approach_iterations = parameter.as_int();
683 if (_max_on_approach_iterations <= 0) {
685 _logger,
"On approach iteration selected as <= 0, "
686 "disabling tolerance and on approach iterations.");
687 _max_on_approach_iterations = std::numeric_limits<int>::max();
689 }
else if (name == _name +
".terminal_checking_interval") {
690 reinit_a_star =
true;
691 _terminal_checking_interval = parameter.as_int();
692 }
else if (name == _name +
".angle_quantization_bins") {
693 reinit_collision_checker =
true;
694 reinit_a_star =
true;
695 int angle_quantizations = parameter.as_int();
696 _angle_bin_size = 2.0 * M_PI / angle_quantizations;
697 _angle_quantizations =
static_cast<unsigned int>(angle_quantizations);
699 }
else if (type == ParameterType::PARAMETER_STRING) {
700 if (name == _name +
".motion_model_for_search") {
701 reinit_a_star =
true;
702 _motion_model = fromString(parameter.as_string());
703 if (_motion_model == MotionModel::UNKNOWN) {
706 "Unable to get MotionModel search type. Given '%s', "
707 "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP.",
708 _motion_model_for_search.c_str());
715 if (reinit_a_star || reinit_downsampler || reinit_collision_checker || reinit_smoother) {
717 if (!_downsample_costmap) {
718 _downsampling_factor = 1;
720 _search_info.minimum_turning_radius =
721 _minimum_turning_radius_global_coords / (_costmap->
getResolution() * _downsampling_factor);
723 static_cast<float>(_lookup_table_size) /
724 static_cast<float>(_costmap->
getResolution() * _downsampling_factor);
727 _lookup_table_dim =
static_cast<float>(
static_cast<int>(_lookup_table_dim));
730 if (
static_cast<int>(_lookup_table_dim) % 2 == 0) {
733 "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
735 _lookup_table_dim += 1.0;
738 auto node = _node.lock();
742 _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
746 _max_on_approach_iterations,
747 _terminal_checking_interval,
750 _angle_quantizations);
754 if (reinit_downsampler) {
755 if (_downsample_costmap && _downsampling_factor > 1) {
756 std::string topic_name =
"downsampled_costmap";
757 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
758 _costmap_downsampler->on_configure(
759 node, _global_frame, topic_name, _costmap, _downsampling_factor);
764 if (reinit_collision_checker) {
767 _costmap_ros->getRobotFootprint(),
768 _costmap_ros->getUseRadius(),
769 findCircumscribedCost(_costmap_ros));
773 if (reinit_smoother) {
775 params.
get(node, _name);
776 _smoother = std::make_unique<Smoother>(params);
777 _smoother->initialize(_minimum_turning_radius_global_coords);
780 result.successful =
true;
786 #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".
double getResolution() const
Accessor for the resolution of the costmap.
bool worldToMapContinuous(double wx, double wy, float &mx, float &my) const
Convert from world coordinates to map coordinates.
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...
static void destroyStaticAssets()
Destroy shared pointer assets at the end of the process that don't require normal destruction handlin...
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.
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.
Parameters for the smoother cost function.
void get(std::shared_ptr< rclcpp_lifecycle::LifecycleNode > node, const std::string &name)
Get params from ROS parameter.