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_ros(nullptr),
39 _costmap_downsampler(nullptr)
46 _logger,
"Destroying plugin %s of type SmacPlannerHybrid",
51 const nav2::LifecycleNode::WeakPtr & parent,
52 std::string name, std::shared_ptr<tf2_ros::Buffer>,
53 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
56 auto node = parent.lock();
57 _logger = node->get_logger();
58 _clock = node->get_clock();
59 _costmap = costmap_ros->getCostmap();
60 _costmap_ros = costmap_ros;
62 _global_frame = costmap_ros->getGlobalFrameID();
64 RCLCPP_INFO(_logger,
"Configuring %s of type SmacPlannerHybrid", name.c_str());
66 int angle_quantizations;
67 double analytic_expansion_max_length_m;
71 nav2::declare_parameter_if_not_declared(
72 node, name +
".downsample_costmap", rclcpp::ParameterValue(
false));
73 node->get_parameter(name +
".downsample_costmap", _downsample_costmap);
74 nav2::declare_parameter_if_not_declared(
75 node, name +
".downsampling_factor", rclcpp::ParameterValue(1));
76 node->get_parameter(name +
".downsampling_factor", _downsampling_factor);
78 nav2::declare_parameter_if_not_declared(
79 node, name +
".angle_quantization_bins", rclcpp::ParameterValue(72));
80 node->get_parameter(name +
".angle_quantization_bins", angle_quantizations);
81 _angle_bin_size = 2.0 * M_PI / angle_quantizations;
82 _angle_quantizations =
static_cast<unsigned int>(angle_quantizations);
84 nav2::declare_parameter_if_not_declared(
85 node, name +
".tolerance", rclcpp::ParameterValue(0.25));
86 _tolerance =
static_cast<float>(node->get_parameter(name +
".tolerance").as_double());
87 nav2::declare_parameter_if_not_declared(
88 node, name +
".allow_unknown", rclcpp::ParameterValue(
true));
89 node->get_parameter(name +
".allow_unknown", _allow_unknown);
90 nav2::declare_parameter_if_not_declared(
91 node, name +
".max_iterations", rclcpp::ParameterValue(1000000));
92 node->get_parameter(name +
".max_iterations", _max_iterations);
93 nav2::declare_parameter_if_not_declared(
94 node, name +
".max_on_approach_iterations", rclcpp::ParameterValue(1000));
95 node->get_parameter(name +
".max_on_approach_iterations", _max_on_approach_iterations);
96 nav2::declare_parameter_if_not_declared(
97 node, name +
".terminal_checking_interval", rclcpp::ParameterValue(5000));
98 node->get_parameter(name +
".terminal_checking_interval", _terminal_checking_interval);
99 nav2::declare_parameter_if_not_declared(
100 node, name +
".smooth_path", rclcpp::ParameterValue(
true));
101 node->get_parameter(name +
".smooth_path", smooth_path);
103 nav2::declare_parameter_if_not_declared(
104 node, name +
".minimum_turning_radius", rclcpp::ParameterValue(0.4));
105 node->get_parameter(name +
".minimum_turning_radius", _minimum_turning_radius_global_coords);
106 nav2::declare_parameter_if_not_declared(
107 node, name +
".allow_primitive_interpolation", rclcpp::ParameterValue(
false));
109 name +
".allow_primitive_interpolation", _search_info.allow_primitive_interpolation);
110 nav2::declare_parameter_if_not_declared(
111 node, name +
".cache_obstacle_heuristic", rclcpp::ParameterValue(
false));
112 node->get_parameter(name +
".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic);
113 nav2::declare_parameter_if_not_declared(
114 node, name +
".reverse_penalty", rclcpp::ParameterValue(2.0));
115 node->get_parameter(name +
".reverse_penalty", _search_info.reverse_penalty);
116 nav2::declare_parameter_if_not_declared(
117 node, name +
".change_penalty", rclcpp::ParameterValue(0.0));
118 node->get_parameter(name +
".change_penalty", _search_info.change_penalty);
119 nav2::declare_parameter_if_not_declared(
120 node, name +
".non_straight_penalty", rclcpp::ParameterValue(1.2));
121 node->get_parameter(name +
".non_straight_penalty", _search_info.non_straight_penalty);
122 nav2::declare_parameter_if_not_declared(
123 node, name +
".cost_penalty", rclcpp::ParameterValue(2.0));
124 node->get_parameter(name +
".cost_penalty", _search_info.cost_penalty);
125 nav2::declare_parameter_if_not_declared(
126 node, name +
".retrospective_penalty", rclcpp::ParameterValue(0.015));
127 node->get_parameter(name +
".retrospective_penalty", _search_info.retrospective_penalty);
128 nav2::declare_parameter_if_not_declared(
129 node, name +
".analytic_expansion_ratio", rclcpp::ParameterValue(3.5));
130 node->get_parameter(name +
".analytic_expansion_ratio", _search_info.analytic_expansion_ratio);
131 nav2::declare_parameter_if_not_declared(
132 node, name +
".analytic_expansion_max_cost", rclcpp::ParameterValue(200.0));
134 name +
".analytic_expansion_max_cost", _search_info.analytic_expansion_max_cost);
135 nav2::declare_parameter_if_not_declared(
136 node, name +
".analytic_expansion_max_cost_override", rclcpp::ParameterValue(
false));
138 name +
".analytic_expansion_max_cost_override",
139 _search_info.analytic_expansion_max_cost_override);
140 nav2::declare_parameter_if_not_declared(
141 node, name +
".use_quadratic_cost_penalty", rclcpp::ParameterValue(
false));
143 name +
".use_quadratic_cost_penalty", _search_info.use_quadratic_cost_penalty);
144 nav2::declare_parameter_if_not_declared(
145 node, name +
".downsample_obstacle_heuristic", rclcpp::ParameterValue(
true));
147 name +
".downsample_obstacle_heuristic", _search_info.downsample_obstacle_heuristic);
149 nav2::declare_parameter_if_not_declared(
150 node, name +
".analytic_expansion_max_length", rclcpp::ParameterValue(3.0));
151 node->get_parameter(name +
".analytic_expansion_max_length", analytic_expansion_max_length_m);
152 _search_info.analytic_expansion_max_length =
155 nav2::declare_parameter_if_not_declared(
156 node, name +
".max_planning_time", rclcpp::ParameterValue(5.0));
157 node->get_parameter(name +
".max_planning_time", _max_planning_time);
158 nav2::declare_parameter_if_not_declared(
159 node, name +
".lookup_table_size", rclcpp::ParameterValue(20.0));
160 node->get_parameter(name +
".lookup_table_size", _lookup_table_size);
162 nav2::declare_parameter_if_not_declared(
163 node, name +
".debug_visualizations", rclcpp::ParameterValue(
false));
164 node->get_parameter(name +
".debug_visualizations", _debug_visualizations);
166 nav2::declare_parameter_if_not_declared(
167 node, name +
".motion_model_for_search", rclcpp::ParameterValue(std::string(
"DUBIN")));
168 node->get_parameter(name +
".motion_model_for_search", _motion_model_for_search);
171 nav2::declare_parameter_if_not_declared(
172 node,
"introspection_mode", rclcpp::ParameterValue(
"disabled"));
174 std::string goal_heading_type;
175 nav2::declare_parameter_if_not_declared(
176 node, name +
".goal_heading_mode", rclcpp::ParameterValue(
"DEFAULT"));
177 node->get_parameter(name +
".goal_heading_mode", goal_heading_type);
178 _goal_heading_mode = fromStringToGH(goal_heading_type);
180 nav2::declare_parameter_if_not_declared(
181 node, name +
".coarse_search_resolution", rclcpp::ParameterValue(1));
182 node->get_parameter(name +
".coarse_search_resolution", _coarse_search_resolution);
184 if (_goal_heading_mode == GoalHeadingMode::UNKNOWN) {
185 std::string error_msg =
"Unable to get GoalHeader type. Given '" + goal_heading_type +
"' "
186 "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ";
190 _motion_model = fromString(_motion_model_for_search);
192 if (_motion_model == MotionModel::UNKNOWN) {
195 "Unable to get MotionModel search type. Given '%s', "
196 "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP, STATE_LATTICE.",
197 _motion_model_for_search.c_str());
200 if (_max_on_approach_iterations <= 0) {
202 _logger,
"On approach iteration selected as <= 0, "
203 "disabling tolerance and on approach iterations.");
204 _max_on_approach_iterations = std::numeric_limits<int>::max();
207 if (_max_iterations <= 0) {
209 _logger,
"maximum iteration selected as <= 0, "
210 "disabling maximum iterations.");
211 _max_iterations = std::numeric_limits<int>::max();
214 if (_coarse_search_resolution <= 0) {
216 _logger,
"coarse iteration resolution selected as <= 0, "
217 "disabling coarse iteration resolution search for goal heading"
220 _coarse_search_resolution = 1;
223 if (_angle_quantizations % _coarse_search_resolution != 0) {
224 std::string error_msg =
"coarse iteration should be an increment"
225 " of the number of angular bins configured";
229 if (_minimum_turning_radius_global_coords < _costmap->getResolution() * _downsampling_factor) {
231 _logger,
"Min turning radius cannot be less than the search grid cell resolution!");
232 _minimum_turning_radius_global_coords = _costmap->
getResolution() * _downsampling_factor;
236 if (!_downsample_costmap) {
237 _downsampling_factor = 1;
239 _search_info.minimum_turning_radius =
240 _minimum_turning_radius_global_coords / (_costmap->
getResolution() * _downsampling_factor);
242 static_cast<float>(_lookup_table_size) /
243 static_cast<float>(_costmap->
getResolution() * _downsampling_factor);
246 _lookup_table_dim =
static_cast<float>(
static_cast<int>(_lookup_table_dim));
249 if (
static_cast<int>(_lookup_table_dim) % 2 == 0) {
252 "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
254 _lookup_table_dim += 1.0;
260 _costmap_ros->getRobotFootprint(),
261 _costmap_ros->getUseRadius(),
262 findCircumscribedCost(_costmap_ros));
265 _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
269 _max_on_approach_iterations,
270 _terminal_checking_interval,
273 _angle_quantizations);
278 params.
get(node, name);
279 _smoother = std::make_unique<Smoother>(params);
280 _smoother->initialize(_minimum_turning_radius_global_coords);
284 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
285 std::string topic_name =
"downsampled_costmap";
286 _costmap_downsampler->on_configure(
287 node, _global_frame, topic_name, _costmap, _downsampling_factor);
289 _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>(
"unsmoothed_plan");
291 if (_debug_visualizations) {
292 _expansions_publisher = node->create_publisher<geometry_msgs::msg::PoseArray>(
"expansions");
293 _planned_footprints_publisher = node->create_publisher<visualization_msgs::msg::MarkerArray>(
294 "planned_footprints");
295 _smoothed_footprints_publisher =
296 node->create_publisher<visualization_msgs::msg::MarkerArray>(
297 "smoothed_footprints");
301 _logger,
"Configured plugin %s of type SmacPlannerHybrid with "
302 "maximum iterations %i, max on approach iterations %i, and %s. Tolerance %.2f."
303 "Using motion model: %s.",
304 _name.c_str(), _max_iterations, _max_on_approach_iterations,
305 _allow_unknown ?
"allowing unknown traversal" :
"not allowing unknown traversal",
306 _tolerance, toString(_motion_model).c_str());
312 _logger,
"Activating plugin %s of type SmacPlannerHybrid",
314 _raw_plan_publisher->on_activate();
315 if (_debug_visualizations) {
316 _expansions_publisher->on_activate();
317 _planned_footprints_publisher->on_activate();
318 _smoothed_footprints_publisher->on_activate();
320 if (_costmap_downsampler) {
321 _costmap_downsampler->on_activate();
323 auto node = _node.lock();
325 _dyn_params_handler = node->add_on_set_parameters_callback(
329 auto resolution_remote_cb = [
this](
const rclcpp::Parameter & p) {
331 {rclcpp::Parameter(
"resolution", rclcpp::ParameterValue(p.as_double()))});
333 _remote_param_subscriber = std::make_shared<rclcpp::ParameterEventHandler>(_node.lock());
334 _remote_resolution_handler = _remote_param_subscriber->add_parameter_callback(
335 "resolution", resolution_remote_cb,
"global_costmap/global_costmap");
341 _logger,
"Deactivating plugin %s of type SmacPlannerHybrid",
343 _raw_plan_publisher->on_deactivate();
344 if (_debug_visualizations) {
345 _expansions_publisher->on_deactivate();
346 _planned_footprints_publisher->on_deactivate();
347 _smoothed_footprints_publisher->on_deactivate();
349 if (_costmap_downsampler) {
350 _costmap_downsampler->on_deactivate();
353 auto node = _node.lock();
354 if (_dyn_params_handler && node) {
355 node->remove_on_set_parameters_callback(_dyn_params_handler.get());
357 _dyn_params_handler.reset();
363 _logger,
"Cleaning up plugin %s of type SmacPlannerHybrid",
368 if (_costmap_downsampler) {
369 _costmap_downsampler->on_cleanup();
370 _costmap_downsampler.reset();
372 _raw_plan_publisher.reset();
373 if (_debug_visualizations) {
374 _expansions_publisher.reset();
375 _planned_footprints_publisher.reset();
376 _smoothed_footprints_publisher.reset();
381 const geometry_msgs::msg::PoseStamped & start,
382 const geometry_msgs::msg::PoseStamped & goal,
383 std::function<
bool()> cancel_checker)
385 std::lock_guard<std::mutex> lock_reinit(_mutex);
386 steady_clock::time_point a = steady_clock::now();
388 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
392 if (_downsample_costmap && _downsampling_factor > 1) {
393 costmap = _costmap_downsampler->downsample(_downsampling_factor);
399 _costmap_ros->getRobotFootprint(),
400 _costmap_ros->getUseRadius(),
401 findCircumscribedCost(_costmap_ros));
402 _a_star->setCollisionChecker(&_collision_checker);
405 float mx_start, my_start, mx_goal, my_goal;
407 start.pose.position.x,
408 start.pose.position.y,
413 "Start Coordinates of(" + std::to_string(start.pose.position.x) +
", " +
414 std::to_string(start.pose.position.y) +
") was outside bounds");
417 double start_orientation_bin = std::round(tf2::getYaw(start.pose.orientation) / _angle_bin_size);
418 while (start_orientation_bin < 0.0) {
419 start_orientation_bin +=
static_cast<float>(_angle_quantizations);
422 if (start_orientation_bin >=
static_cast<float>(_angle_quantizations)) {
423 start_orientation_bin -=
static_cast<float>(_angle_quantizations);
425 unsigned int start_orientation_bin_int =
426 static_cast<unsigned int>(start_orientation_bin);
427 _a_star->setStart(mx_start, my_start, start_orientation_bin_int);
431 goal.pose.position.x,
432 goal.pose.position.y,
437 "Goal Coordinates of(" + std::to_string(goal.pose.position.x) +
", " +
438 std::to_string(goal.pose.position.y) +
") was outside bounds");
440 double goal_orientation_bin = std::round(tf2::getYaw(goal.pose.orientation) / _angle_bin_size);
441 while (goal_orientation_bin < 0.0) {
442 goal_orientation_bin +=
static_cast<float>(_angle_quantizations);
445 if (goal_orientation_bin >=
static_cast<float>(_angle_quantizations)) {
446 goal_orientation_bin -=
static_cast<float>(_angle_quantizations);
448 unsigned int goal_orientation_bin_int =
449 static_cast<unsigned int>(goal_orientation_bin);
450 _a_star->setGoal(mx_goal, my_goal,
static_cast<unsigned int>(goal_orientation_bin_int),
451 _goal_heading_mode, _coarse_search_resolution);
454 nav_msgs::msg::Path plan;
455 plan.header.stamp = _clock->now();
456 plan.header.frame_id = _global_frame;
457 geometry_msgs::msg::PoseStamped pose;
458 pose.header = plan.header;
459 pose.pose.position.z = 0.0;
460 pose.pose.orientation.x = 0.0;
461 pose.pose.orientation.y = 0.0;
462 pose.pose.orientation.z = 0.0;
463 pose.pose.orientation.w = 1.0;
466 if (std::floor(mx_start) == std::floor(mx_goal) &&
467 std::floor(my_start) == std::floor(my_goal) &&
468 start_orientation_bin_int == goal_orientation_bin_int)
470 pose.pose = start.pose;
471 pose.pose.orientation = goal.pose.orientation;
472 plan.poses.push_back(pose);
475 if (_raw_plan_publisher->get_subscription_count() > 0) {
476 _raw_plan_publisher->publish(plan);
483 NodeHybrid::CoordinateVector path;
484 int num_iterations = 0;
486 std::unique_ptr<std::vector<std::tuple<float, float, float>>> expansions =
nullptr;
487 if (_debug_visualizations) {
488 expansions = std::make_unique<std::vector<std::tuple<float, float, float>>>();
491 if (!_a_star->createPath(
492 path, num_iterations,
493 _tolerance /
static_cast<float>(costmap->
getResolution()), cancel_checker, expansions.get()))
495 if (_debug_visualizations) {
496 geometry_msgs::msg::PoseArray msg;
497 geometry_msgs::msg::Pose msg_pose;
498 msg.header.stamp = _clock->now();
499 msg.header.frame_id = _global_frame;
500 for (
auto & e : *expansions) {
501 msg_pose.position.x = std::get<0>(e);
502 msg_pose.position.y = std::get<1>(e);
503 msg_pose.orientation = getWorldOrientation(std::get<2>(e));
504 msg.poses.push_back(msg_pose);
506 _expansions_publisher->publish(msg);
510 if (num_iterations == 1) {
514 if (num_iterations < _a_star->getMaxIterations()) {
522 plan.poses.reserve(path.size());
523 for (
int i = path.size() - 1; i >= 0; --i) {
524 pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
525 pose.pose.orientation = getWorldOrientation(path[i].theta);
526 plan.poses.push_back(pose);
530 if (_raw_plan_publisher->get_subscription_count() > 0) {
531 _raw_plan_publisher->publish(plan);
534 if (_debug_visualizations) {
536 auto now = _clock->now();
537 geometry_msgs::msg::PoseArray msg;
538 geometry_msgs::msg::Pose msg_pose;
539 msg.header.stamp = now;
540 msg.header.frame_id = _global_frame;
541 for (
auto & e : *expansions) {
542 msg_pose.position.x = std::get<0>(e);
543 msg_pose.position.y = std::get<1>(e);
544 msg_pose.orientation = getWorldOrientation(std::get<2>(e));
545 msg.poses.push_back(msg_pose);
547 _expansions_publisher->publish(msg);
549 if (_planned_footprints_publisher->get_subscription_count() > 0) {
551 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
552 visualization_msgs::msg::Marker clear_all_marker;
553 clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
554 marker_array->markers.push_back(clear_all_marker);
555 _planned_footprints_publisher->publish(std::move(marker_array));
558 marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
559 for (
size_t i = 0; i < plan.poses.size(); i++) {
560 const std::vector<geometry_msgs::msg::Point> edge =
561 transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
562 marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
564 _planned_footprints_publisher->publish(std::move(marker_array));
569 steady_clock::time_point b = steady_clock::now();
570 duration<double> time_span = duration_cast<duration<double>>(b - a);
571 double time_remaining = _max_planning_time -
static_cast<double>(time_span.count());
573 #ifdef BENCHMARK_TESTING
574 std::cout <<
"It took " << time_span.count() * 1000 <<
575 " milliseconds with " << num_iterations <<
" iterations." << std::endl;
579 if (_smoother && num_iterations > 1) {
580 _smoother->smooth(plan, costmap, time_remaining);
583 #ifdef BENCHMARK_TESTING
584 steady_clock::time_point c = steady_clock::now();
585 duration<double> time_span2 = duration_cast<duration<double>>(c - b);
586 std::cout <<
"It took " << time_span2.count() * 1000 <<
587 " milliseconds to smooth path." << std::endl;
590 if (_debug_visualizations) {
591 if (_smoothed_footprints_publisher->get_subscription_count() > 0) {
593 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
594 visualization_msgs::msg::Marker clear_all_marker;
595 clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
596 marker_array->markers.push_back(clear_all_marker);
597 _smoothed_footprints_publisher->publish(std::move(marker_array));
600 marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
601 auto now = _clock->now();
602 for (
size_t i = 0; i < plan.poses.size(); i++) {
603 const std::vector<geometry_msgs::msg::Point> edge =
604 transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
605 marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
607 _smoothed_footprints_publisher->publish(std::move(marker_array));
614 rcl_interfaces::msg::SetParametersResult
617 rcl_interfaces::msg::SetParametersResult result;
618 std::lock_guard<std::mutex> lock_reinit(_mutex);
620 bool reinit_collision_checker =
false;
621 bool reinit_a_star =
false;
622 bool reinit_downsampler =
false;
623 bool reinit_smoother =
false;
625 for (
auto parameter : parameters) {
626 const auto & param_type = parameter.get_type();
627 const auto & param_name = parameter.get_name();
628 if(param_name.find(_name +
".") != 0 && param_name !=
"resolution") {
631 if (param_type == ParameterType::PARAMETER_DOUBLE) {
632 if (param_name == _name +
".max_planning_time") {
633 reinit_a_star =
true;
634 _max_planning_time = parameter.as_double();
635 }
else if (param_name == _name +
".tolerance") {
636 _tolerance =
static_cast<float>(parameter.as_double());
637 }
else if (param_name == _name +
".lookup_table_size") {
638 reinit_a_star =
true;
639 _lookup_table_size = parameter.as_double();
640 }
else if (param_name == _name +
".minimum_turning_radius") {
641 reinit_a_star =
true;
643 reinit_smoother =
true;
646 if (parameter.as_double() < _costmap->
getResolution() * _downsampling_factor) {
648 _logger,
"Min turning radius cannot be less than the search grid cell resolution!");
649 result.successful =
false;
652 _minimum_turning_radius_global_coords =
static_cast<float>(parameter.as_double());
653 }
else if (param_name == _name +
".reverse_penalty") {
654 reinit_a_star =
true;
655 _search_info.reverse_penalty =
static_cast<float>(parameter.as_double());
656 }
else if (param_name == _name +
".change_penalty") {
657 reinit_a_star =
true;
658 _search_info.change_penalty =
static_cast<float>(parameter.as_double());
659 }
else if (param_name == _name +
".non_straight_penalty") {
660 reinit_a_star =
true;
661 _search_info.non_straight_penalty =
static_cast<float>(parameter.as_double());
662 }
else if (param_name == _name +
".cost_penalty") {
663 reinit_a_star =
true;
664 _search_info.cost_penalty =
static_cast<float>(parameter.as_double());
665 }
else if (param_name == _name +
".analytic_expansion_ratio") {
666 reinit_a_star =
true;
667 _search_info.analytic_expansion_ratio =
static_cast<float>(parameter.as_double());
668 }
else if (param_name == _name +
".analytic_expansion_max_length") {
669 reinit_a_star =
true;
670 _search_info.analytic_expansion_max_length =
671 static_cast<float>(parameter.as_double()) / _costmap->
getResolution();
672 }
else if (param_name == _name +
".analytic_expansion_max_cost") {
673 reinit_a_star =
true;
674 _search_info.analytic_expansion_max_cost =
static_cast<float>(parameter.as_double());
675 }
else if (param_name ==
"resolution") {
678 RCLCPP_INFO(_logger,
"Costmap resolution changed. Reinitializing SmacPlannerHybrid.");
679 reinit_collision_checker =
true;
680 reinit_a_star =
true;
681 reinit_downsampler =
true;
682 reinit_smoother =
true;
684 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
685 if (param_name == _name +
".downsample_costmap") {
686 reinit_downsampler =
true;
687 _downsample_costmap = parameter.as_bool();
688 }
else if (param_name == _name +
".allow_unknown") {
689 reinit_a_star =
true;
690 _allow_unknown = parameter.as_bool();
691 }
else if (param_name == _name +
".cache_obstacle_heuristic") {
692 reinit_a_star =
true;
693 _search_info.cache_obstacle_heuristic = parameter.as_bool();
694 }
else if (param_name == _name +
".allow_primitive_interpolation") {
695 _search_info.allow_primitive_interpolation = parameter.as_bool();
696 reinit_a_star =
true;
697 }
else if (param_name == _name +
".smooth_path") {
698 if (parameter.as_bool()) {
699 reinit_smoother =
true;
703 }
else if (param_name == _name +
".analytic_expansion_max_cost_override") {
704 _search_info.analytic_expansion_max_cost_override = parameter.as_bool();
705 reinit_a_star =
true;
707 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
708 if (param_name == _name +
".downsampling_factor") {
709 reinit_a_star =
true;
710 reinit_downsampler =
true;
711 _downsampling_factor = parameter.as_int();
712 }
else if (param_name == _name +
".max_iterations") {
713 reinit_a_star =
true;
714 _max_iterations = parameter.as_int();
715 if (_max_iterations <= 0) {
717 _logger,
"maximum iteration selected as <= 0, "
718 "disabling maximum iterations.");
719 _max_iterations = std::numeric_limits<int>::max();
721 }
else if (param_name == _name +
".max_on_approach_iterations") {
722 reinit_a_star =
true;
723 _max_on_approach_iterations = parameter.as_int();
724 if (_max_on_approach_iterations <= 0) {
726 _logger,
"On approach iteration selected as <= 0, "
727 "disabling tolerance and on approach iterations.");
728 _max_on_approach_iterations = std::numeric_limits<int>::max();
730 }
else if (param_name == _name +
".terminal_checking_interval") {
731 reinit_a_star =
true;
732 _terminal_checking_interval = parameter.as_int();
733 }
else if (param_name == _name +
".angle_quantization_bins") {
734 reinit_collision_checker =
true;
735 reinit_a_star =
true;
736 int angle_quantizations = parameter.as_int();
737 _angle_bin_size = 2.0 * M_PI / angle_quantizations;
738 _angle_quantizations =
static_cast<unsigned int>(angle_quantizations);
740 if (_angle_quantizations % _coarse_search_resolution != 0) {
742 _logger,
"coarse iteration should be an increment of the "
743 "number of angular bins configured. Disabling course research!"
745 _coarse_search_resolution = 1;
747 }
else if (param_name == _name +
".coarse_search_resolution") {
748 _coarse_search_resolution = parameter.as_int();
749 if (_coarse_search_resolution <= 0) {
751 _logger,
"coarse iteration resolution selected as <= 0. "
752 "Disabling course research!"
754 _coarse_search_resolution = 1;
756 if (_angle_quantizations % _coarse_search_resolution != 0) {
759 "coarse iteration should be an increment of the "
760 "number of angular bins configured. Disabling course research!"
762 _coarse_search_resolution = 1;
765 }
else if (param_type == ParameterType::PARAMETER_STRING) {
766 if (param_name == _name +
".motion_model_for_search") {
767 reinit_a_star =
true;
768 _motion_model = fromString(parameter.as_string());
769 if (_motion_model == MotionModel::UNKNOWN) {
772 "Unable to get MotionModel search type. Given '%s', "
773 "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP.",
774 _motion_model_for_search.c_str());
776 }
else if (param_name == _name +
".goal_heading_mode") {
777 std::string goal_heading_type = parameter.as_string();
778 GoalHeadingMode goal_heading_mode = fromStringToGH(goal_heading_type);
781 "GoalHeadingMode type set to '%s'.",
782 goal_heading_type.c_str());
783 if (goal_heading_mode == GoalHeadingMode::UNKNOWN) {
786 "Unable to get GoalHeader type. Given '%s', "
787 "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ",
788 goal_heading_type.c_str());
790 _goal_heading_mode = goal_heading_mode;
797 if (reinit_a_star || reinit_downsampler || reinit_collision_checker || reinit_smoother) {
799 if (!_downsample_costmap) {
800 _downsampling_factor = 1;
802 _search_info.minimum_turning_radius =
803 _minimum_turning_radius_global_coords / (_costmap->
getResolution() * _downsampling_factor);
805 static_cast<float>(_lookup_table_size) /
806 static_cast<float>(_costmap->
getResolution() * _downsampling_factor);
809 _lookup_table_dim =
static_cast<float>(
static_cast<int>(_lookup_table_dim));
812 if (
static_cast<int>(_lookup_table_dim) % 2 == 0) {
815 "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
817 _lookup_table_dim += 1.0;
820 auto node = _node.lock();
824 _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
828 _max_on_approach_iterations,
829 _terminal_checking_interval,
832 _angle_quantizations);
836 if (reinit_downsampler) {
837 if (_downsample_costmap && _downsampling_factor > 1) {
838 std::string topic_name =
"downsampled_costmap";
839 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
840 _costmap_downsampler->on_configure(
841 node, _global_frame, topic_name, _costmap, _downsampling_factor);
842 _costmap_downsampler->on_activate();
847 if (reinit_collision_checker) {
850 _costmap_ros->getRobotFootprint(),
851 _costmap_ros->getUseRadius(),
852 findCircumscribedCost(_costmap_ros));
856 if (reinit_smoother) {
858 params.
get(node, _name);
859 _smoother = std::make_unique<Smoother>(params);
860 _smoother->initialize(_minimum_turning_radius_global_coords);
863 result.successful =
true;
869 #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...
void configure(const nav2::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.
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 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 parameter change is detected.
Parameters for the smoother cost function.
void get(nav2::LifecycleNode::SharedPtr node, const std::string &name)
Get params from ROS parameter.