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 rclcpp_lifecycle::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_util::declare_parameter_if_not_declared(
72 node, name +
".downsample_costmap", rclcpp::ParameterValue(
false));
73 node->get_parameter(name +
".downsample_costmap", _downsample_costmap);
74 nav2_util::declare_parameter_if_not_declared(
75 node, name +
".downsampling_factor", rclcpp::ParameterValue(1));
76 node->get_parameter(name +
".downsampling_factor", _downsampling_factor);
78 nav2_util::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_util::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_util::declare_parameter_if_not_declared(
88 node, name +
".allow_unknown", rclcpp::ParameterValue(
true));
89 node->get_parameter(name +
".allow_unknown", _allow_unknown);
90 nav2_util::declare_parameter_if_not_declared(
91 node, name +
".max_iterations", rclcpp::ParameterValue(1000000));
92 node->get_parameter(name +
".max_iterations", _max_iterations);
93 nav2_util::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_util::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_util::declare_parameter_if_not_declared(
100 node, name +
".smooth_path", rclcpp::ParameterValue(
true));
101 node->get_parameter(name +
".smooth_path", smooth_path);
103 nav2_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::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_util::declare_parameter_if_not_declared(
163 node, name +
".debug_visualizations", rclcpp::ParameterValue(
false));
164 node->get_parameter(name +
".debug_visualizations", _debug_visualizations);
166 nav2_util::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_util::declare_parameter_if_not_declared(
172 node,
"service_introspection_mode", rclcpp::ParameterValue(
"disabled"));
174 std::string goal_heading_type;
175 nav2_util::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_util::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);
277 params.
get(node, name);
279 _smoother = std::make_unique<Smoother>(params);
280 _smoother->initialize(_minimum_turning_radius_global_coords);
284 if (_downsample_costmap && _downsampling_factor > 1) {
285 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
286 std::string topic_name =
"downsampled_costmap";
287 _costmap_downsampler->on_configure(
288 node, _global_frame, topic_name, _costmap, _downsampling_factor);
291 _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>(
"unsmoothed_plan", 1);
293 if (_debug_visualizations) {
294 _expansions_publisher = node->create_publisher<geometry_msgs::msg::PoseArray>(
"expansions", 1);
295 _planned_footprints_publisher = node->create_publisher<visualization_msgs::msg::MarkerArray>(
296 "planned_footprints", 1);
297 _smoothed_footprints_publisher =
298 node->create_publisher<visualization_msgs::msg::MarkerArray>(
299 "smoothed_footprints", 1);
303 _logger,
"Configured plugin %s of type SmacPlannerHybrid with "
304 "maximum iterations %i, max on approach iterations %i, and %s. Tolerance %.2f."
305 "Using motion model: %s.",
306 _name.c_str(), _max_iterations, _max_on_approach_iterations,
307 _allow_unknown ?
"allowing unknown traversal" :
"not allowing unknown traversal",
308 _tolerance, toString(_motion_model).c_str());
314 _logger,
"Activating plugin %s of type SmacPlannerHybrid",
316 _raw_plan_publisher->on_activate();
317 if (_debug_visualizations) {
318 _expansions_publisher->on_activate();
319 _planned_footprints_publisher->on_activate();
320 _smoothed_footprints_publisher->on_activate();
322 if (_costmap_downsampler) {
323 _costmap_downsampler->on_activate();
325 auto node = _node.lock();
327 _dyn_params_handler = node->add_on_set_parameters_callback(
331 auto resolution_remote_cb = [
this](
const rclcpp::Parameter & p) {
333 {rclcpp::Parameter(
"resolution", rclcpp::ParameterValue(p.as_double()))});
335 _remote_param_subscriber = std::make_shared<rclcpp::ParameterEventHandler>(_node.lock());
336 _remote_resolution_handler = _remote_param_subscriber->add_parameter_callback(
337 "resolution", resolution_remote_cb,
"global_costmap/global_costmap");
343 _logger,
"Deactivating plugin %s of type SmacPlannerHybrid",
345 _raw_plan_publisher->on_deactivate();
346 if (_debug_visualizations) {
347 _expansions_publisher->on_deactivate();
348 _planned_footprints_publisher->on_deactivate();
349 _smoothed_footprints_publisher->on_deactivate();
351 if (_costmap_downsampler) {
352 _costmap_downsampler->on_deactivate();
355 auto node = _node.lock();
356 if (_dyn_params_handler && node) {
357 node->remove_on_set_parameters_callback(_dyn_params_handler.get());
359 _dyn_params_handler.reset();
365 _logger,
"Cleaning up plugin %s of type SmacPlannerHybrid",
370 if (_costmap_downsampler) {
371 _costmap_downsampler->on_cleanup();
372 _costmap_downsampler.reset();
374 _raw_plan_publisher.reset();
375 if (_debug_visualizations) {
376 _expansions_publisher.reset();
377 _planned_footprints_publisher.reset();
378 _smoothed_footprints_publisher.reset();
383 const geometry_msgs::msg::PoseStamped & start,
384 const geometry_msgs::msg::PoseStamped & goal,
385 std::function<
bool()> cancel_checker)
387 std::lock_guard<std::mutex> lock_reinit(_mutex);
388 steady_clock::time_point a = steady_clock::now();
390 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
394 if (_costmap_downsampler) {
395 costmap = _costmap_downsampler->downsample(_downsampling_factor);
401 _costmap_ros->getRobotFootprint(),
402 _costmap_ros->getUseRadius(),
403 findCircumscribedCost(_costmap_ros));
404 _a_star->setCollisionChecker(&_collision_checker);
407 float mx_start, my_start, mx_goal, my_goal;
409 start.pose.position.x,
410 start.pose.position.y,
415 "Start Coordinates of(" + std::to_string(start.pose.position.x) +
", " +
416 std::to_string(start.pose.position.y) +
") was outside bounds");
419 double start_orientation_bin = std::round(tf2::getYaw(start.pose.orientation) / _angle_bin_size);
420 while (start_orientation_bin < 0.0) {
421 start_orientation_bin +=
static_cast<float>(_angle_quantizations);
424 if (start_orientation_bin >=
static_cast<float>(_angle_quantizations)) {
425 start_orientation_bin -=
static_cast<float>(_angle_quantizations);
427 unsigned int start_orientation_bin_int =
428 static_cast<unsigned int>(start_orientation_bin);
429 _a_star->setStart(mx_start, my_start, start_orientation_bin_int);
433 goal.pose.position.x,
434 goal.pose.position.y,
439 "Goal Coordinates of(" + std::to_string(goal.pose.position.x) +
", " +
440 std::to_string(goal.pose.position.y) +
") was outside bounds");
442 double goal_orientation_bin = std::round(tf2::getYaw(goal.pose.orientation) / _angle_bin_size);
443 while (goal_orientation_bin < 0.0) {
444 goal_orientation_bin +=
static_cast<float>(_angle_quantizations);
447 if (goal_orientation_bin >=
static_cast<float>(_angle_quantizations)) {
448 goal_orientation_bin -=
static_cast<float>(_angle_quantizations);
450 unsigned int goal_orientation_bin_int =
451 static_cast<unsigned int>(goal_orientation_bin);
452 _a_star->setGoal(mx_goal, my_goal,
static_cast<unsigned int>(goal_orientation_bin_int),
453 _goal_heading_mode, _coarse_search_resolution);
456 nav_msgs::msg::Path plan;
457 plan.header.stamp = _clock->now();
458 plan.header.frame_id = _global_frame;
459 geometry_msgs::msg::PoseStamped pose;
460 pose.header = plan.header;
461 pose.pose.position.z = 0.0;
462 pose.pose.orientation.x = 0.0;
463 pose.pose.orientation.y = 0.0;
464 pose.pose.orientation.z = 0.0;
465 pose.pose.orientation.w = 1.0;
468 if (std::floor(mx_start) == std::floor(mx_goal) &&
469 std::floor(my_start) == std::floor(my_goal) &&
470 start_orientation_bin_int == goal_orientation_bin_int)
472 pose.pose = start.pose;
473 pose.pose.orientation = goal.pose.orientation;
474 plan.poses.push_back(pose);
477 if (_raw_plan_publisher->get_subscription_count() > 0) {
478 _raw_plan_publisher->publish(plan);
485 NodeHybrid::CoordinateVector path;
486 int num_iterations = 0;
488 std::unique_ptr<std::vector<std::tuple<float, float, float>>> expansions =
nullptr;
489 if (_debug_visualizations) {
490 expansions = std::make_unique<std::vector<std::tuple<float, float, float>>>();
493 if (!_a_star->createPath(
494 path, num_iterations,
495 _tolerance /
static_cast<float>(costmap->
getResolution()), cancel_checker, expansions.get()))
497 if (_debug_visualizations) {
498 geometry_msgs::msg::PoseArray msg;
499 geometry_msgs::msg::Pose msg_pose;
500 msg.header.stamp = _clock->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);
512 if (num_iterations == 1) {
516 if (num_iterations < _a_star->getMaxIterations()) {
524 plan.poses.reserve(path.size());
525 for (
int i = path.size() - 1; i >= 0; --i) {
526 pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
527 pose.pose.orientation = getWorldOrientation(path[i].theta);
528 plan.poses.push_back(pose);
532 if (_raw_plan_publisher->get_subscription_count() > 0) {
533 _raw_plan_publisher->publish(plan);
536 if (_debug_visualizations) {
538 auto now = _clock->now();
539 geometry_msgs::msg::PoseArray msg;
540 geometry_msgs::msg::Pose msg_pose;
541 msg.header.stamp = now;
542 msg.header.frame_id = _global_frame;
543 for (
auto & e : *expansions) {
544 msg_pose.position.x = std::get<0>(e);
545 msg_pose.position.y = std::get<1>(e);
546 msg_pose.orientation = getWorldOrientation(std::get<2>(e));
547 msg.poses.push_back(msg_pose);
549 _expansions_publisher->publish(msg);
551 if (_planned_footprints_publisher->get_subscription_count() > 0) {
553 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
554 visualization_msgs::msg::Marker clear_all_marker;
555 clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
556 marker_array->markers.push_back(clear_all_marker);
557 _planned_footprints_publisher->publish(std::move(marker_array));
560 marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
561 for (
size_t i = 0; i < plan.poses.size(); i++) {
562 const std::vector<geometry_msgs::msg::Point> edge =
563 transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
564 marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
566 _planned_footprints_publisher->publish(std::move(marker_array));
571 steady_clock::time_point b = steady_clock::now();
572 duration<double> time_span = duration_cast<duration<double>>(b - a);
573 double time_remaining = _max_planning_time -
static_cast<double>(time_span.count());
575 #ifdef BENCHMARK_TESTING
576 std::cout <<
"It took " << time_span.count() * 1000 <<
577 " milliseconds with " << num_iterations <<
" iterations." << std::endl;
581 if (_smoother && num_iterations > 1) {
582 _smoother->smooth(plan, costmap, time_remaining);
585 #ifdef BENCHMARK_TESTING
586 steady_clock::time_point c = steady_clock::now();
587 duration<double> time_span2 = duration_cast<duration<double>>(c - b);
588 std::cout <<
"It took " << time_span2.count() * 1000 <<
589 " milliseconds to smooth path." << std::endl;
592 if (_debug_visualizations) {
593 if (_smoothed_footprints_publisher->get_subscription_count() > 0) {
595 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
596 visualization_msgs::msg::Marker clear_all_marker;
597 clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
598 marker_array->markers.push_back(clear_all_marker);
599 _smoothed_footprints_publisher->publish(std::move(marker_array));
602 marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
603 auto now = _clock->now();
604 for (
size_t i = 0; i < plan.poses.size(); i++) {
605 const std::vector<geometry_msgs::msg::Point> edge =
606 transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
607 marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
609 _smoothed_footprints_publisher->publish(std::move(marker_array));
616 rcl_interfaces::msg::SetParametersResult
619 rcl_interfaces::msg::SetParametersResult result;
620 std::lock_guard<std::mutex> lock_reinit(_mutex);
622 bool reinit_collision_checker =
false;
623 bool reinit_a_star =
false;
624 bool reinit_downsampler =
false;
625 bool reinit_smoother =
false;
627 for (
auto parameter : parameters) {
628 const auto & param_type = parameter.get_type();
629 const auto & param_name = parameter.get_name();
630 if(param_name.find(_name +
".") != 0 && param_name !=
"resolution") {
633 if (param_type == ParameterType::PARAMETER_DOUBLE) {
634 if (param_name == _name +
".max_planning_time") {
635 reinit_a_star =
true;
636 _max_planning_time = parameter.as_double();
637 }
else if (param_name == _name +
".tolerance") {
638 _tolerance =
static_cast<float>(parameter.as_double());
639 }
else if (param_name == _name +
".lookup_table_size") {
640 reinit_a_star =
true;
641 _lookup_table_size = parameter.as_double();
642 }
else if (param_name == _name +
".minimum_turning_radius") {
643 reinit_a_star =
true;
645 reinit_smoother =
true;
648 if (parameter.as_double() < _costmap->
getResolution() * _downsampling_factor) {
650 _logger,
"Min turning radius cannot be less than the search grid cell resolution!");
651 result.successful =
false;
654 _minimum_turning_radius_global_coords =
static_cast<float>(parameter.as_double());
655 }
else if (param_name == _name +
".reverse_penalty") {
656 reinit_a_star =
true;
657 _search_info.reverse_penalty =
static_cast<float>(parameter.as_double());
658 }
else if (param_name == _name +
".change_penalty") {
659 reinit_a_star =
true;
660 _search_info.change_penalty =
static_cast<float>(parameter.as_double());
661 }
else if (param_name == _name +
".non_straight_penalty") {
662 reinit_a_star =
true;
663 _search_info.non_straight_penalty =
static_cast<float>(parameter.as_double());
664 }
else if (param_name == _name +
".cost_penalty") {
665 reinit_a_star =
true;
666 _search_info.cost_penalty =
static_cast<float>(parameter.as_double());
667 }
else if (param_name == _name +
".analytic_expansion_ratio") {
668 reinit_a_star =
true;
669 _search_info.analytic_expansion_ratio =
static_cast<float>(parameter.as_double());
670 }
else if (param_name == _name +
".analytic_expansion_max_length") {
671 reinit_a_star =
true;
672 _search_info.analytic_expansion_max_length =
673 static_cast<float>(parameter.as_double()) / _costmap->
getResolution();
674 }
else if (param_name == _name +
".analytic_expansion_max_cost") {
675 reinit_a_star =
true;
676 _search_info.analytic_expansion_max_cost =
static_cast<float>(parameter.as_double());
677 }
else if (param_name ==
"resolution") {
680 RCLCPP_INFO(_logger,
"Costmap resolution changed. Reinitializing SmacPlannerHybrid.");
681 reinit_collision_checker =
true;
682 reinit_a_star =
true;
683 reinit_downsampler =
true;
684 reinit_smoother =
true;
686 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
687 if (param_name == _name +
".downsample_costmap") {
688 reinit_downsampler =
true;
689 _downsample_costmap = parameter.as_bool();
690 }
else if (param_name == _name +
".allow_unknown") {
691 reinit_a_star =
true;
692 _allow_unknown = parameter.as_bool();
693 }
else if (param_name == _name +
".cache_obstacle_heuristic") {
694 reinit_a_star =
true;
695 _search_info.cache_obstacle_heuristic = parameter.as_bool();
696 }
else if (param_name == _name +
".allow_primitive_interpolation") {
697 _search_info.allow_primitive_interpolation = parameter.as_bool();
698 reinit_a_star =
true;
699 }
else if (param_name == _name +
".smooth_path") {
700 if (parameter.as_bool()) {
701 reinit_smoother =
true;
705 }
else if (param_name == _name +
".analytic_expansion_max_cost_override") {
706 _search_info.analytic_expansion_max_cost_override = parameter.as_bool();
707 reinit_a_star =
true;
709 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
710 if (param_name == _name +
".downsampling_factor") {
711 reinit_a_star =
true;
712 reinit_downsampler =
true;
713 _downsampling_factor = parameter.as_int();
714 }
else if (param_name == _name +
".max_iterations") {
715 reinit_a_star =
true;
716 _max_iterations = parameter.as_int();
717 if (_max_iterations <= 0) {
719 _logger,
"maximum iteration selected as <= 0, "
720 "disabling maximum iterations.");
721 _max_iterations = std::numeric_limits<int>::max();
723 }
else if (param_name == _name +
".max_on_approach_iterations") {
724 reinit_a_star =
true;
725 _max_on_approach_iterations = parameter.as_int();
726 if (_max_on_approach_iterations <= 0) {
728 _logger,
"On approach iteration selected as <= 0, "
729 "disabling tolerance and on approach iterations.");
730 _max_on_approach_iterations = std::numeric_limits<int>::max();
732 }
else if (param_name == _name +
".terminal_checking_interval") {
733 reinit_a_star =
true;
734 _terminal_checking_interval = parameter.as_int();
735 }
else if (param_name == _name +
".angle_quantization_bins") {
736 reinit_collision_checker =
true;
737 reinit_a_star =
true;
738 int angle_quantizations = parameter.as_int();
739 _angle_bin_size = 2.0 * M_PI / angle_quantizations;
740 _angle_quantizations =
static_cast<unsigned int>(angle_quantizations);
742 if (_angle_quantizations % _coarse_search_resolution != 0) {
744 _logger,
"coarse iteration should be an increment of the "
745 "number of angular bins configured. Disabling course research!"
747 _coarse_search_resolution = 1;
749 }
else if (param_name == _name +
".coarse_search_resolution") {
750 _coarse_search_resolution = parameter.as_int();
751 if (_coarse_search_resolution <= 0) {
753 _logger,
"coarse iteration resolution selected as <= 0. "
754 "Disabling course research!"
756 _coarse_search_resolution = 1;
758 if (_angle_quantizations % _coarse_search_resolution != 0) {
761 "coarse iteration should be an increment of the "
762 "number of angular bins configured. Disabling course research!"
764 _coarse_search_resolution = 1;
767 }
else if (param_type == ParameterType::PARAMETER_STRING) {
768 if (param_name == _name +
".motion_model_for_search") {
769 reinit_a_star =
true;
770 _motion_model = fromString(parameter.as_string());
771 if (_motion_model == MotionModel::UNKNOWN) {
774 "Unable to get MotionModel search type. Given '%s', "
775 "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP.",
776 _motion_model_for_search.c_str());
778 }
else if (param_name == _name +
".goal_heading_mode") {
779 std::string goal_heading_type = parameter.as_string();
780 GoalHeadingMode goal_heading_mode = fromStringToGH(goal_heading_type);
783 "GoalHeadingMode type set to '%s'.",
784 goal_heading_type.c_str());
785 if (goal_heading_mode == GoalHeadingMode::UNKNOWN) {
788 "Unable to get GoalHeader type. Given '%s', "
789 "Valid options are DEFAULT, BIDIRECTIONAL, ALL_DIRECTION. ",
790 goal_heading_type.c_str());
792 _goal_heading_mode = goal_heading_mode;
799 if (reinit_a_star || reinit_downsampler || reinit_collision_checker || reinit_smoother) {
801 if (!_downsample_costmap) {
802 _downsampling_factor = 1;
804 _search_info.minimum_turning_radius =
805 _minimum_turning_radius_global_coords / (_costmap->
getResolution() * _downsampling_factor);
807 static_cast<float>(_lookup_table_size) /
808 static_cast<float>(_costmap->
getResolution() * _downsampling_factor);
811 _lookup_table_dim =
static_cast<float>(
static_cast<int>(_lookup_table_dim));
814 if (
static_cast<int>(_lookup_table_dim) % 2 == 0) {
817 "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
819 _lookup_table_dim += 1.0;
822 auto node = _node.lock();
826 _a_star = std::make_unique<AStarAlgorithm<NodeHybrid>>(_motion_model, _search_info);
830 _max_on_approach_iterations,
831 _terminal_checking_interval,
834 _angle_quantizations);
838 if (reinit_downsampler) {
839 if (_downsample_costmap && _downsampling_factor > 1) {
840 std::string topic_name =
"downsampled_costmap";
841 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
842 _costmap_downsampler->on_configure(
843 node, _global_frame, topic_name, _costmap, _downsampling_factor);
848 if (reinit_collision_checker) {
851 _costmap_ros->getRobotFootprint(),
852 _costmap_ros->getUseRadius(),
853 findCircumscribedCost(_costmap_ros));
857 if (reinit_smoother) {
859 params.
get(node, _name);
860 _smoother = std::make_unique<Smoother>(params);
861 _smoother->initialize(_minimum_turning_radius_global_coords);
864 result.successful =
true;
870 #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 parameter 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.