22 #include "nav2_smac_planner/smac_planner_lattice.hpp"
26 namespace nav2_smac_planner
29 using namespace std::chrono;
30 using rcl_interfaces::msg::ParameterType;
34 _collision_checker(nullptr, 1, nullptr),
43 _logger,
"Destroying plugin %s of type SmacPlannerLattice",
48 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
49 std::string name, std::shared_ptr<tf2_ros::Buffer>,
50 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
53 auto node = parent.lock();
54 _logger = node->get_logger();
55 _clock = node->get_clock();
56 _costmap = costmap_ros->getCostmap();
57 _costmap_ros = costmap_ros;
59 _global_frame = costmap_ros->getGlobalFrameID();
61 RCLCPP_INFO(_logger,
"Configuring %s of type SmacPlannerLattice", name.c_str());
64 double analytic_expansion_max_length_m;
67 nav2_util::declare_parameter_if_not_declared(
68 node, name +
".tolerance", rclcpp::ParameterValue(0.25));
69 _tolerance =
static_cast<float>(node->get_parameter(name +
".tolerance").as_double());
70 nav2_util::declare_parameter_if_not_declared(
71 node, name +
".allow_unknown", rclcpp::ParameterValue(
true));
72 node->get_parameter(name +
".allow_unknown", _allow_unknown);
73 nav2_util::declare_parameter_if_not_declared(
74 node, name +
".max_iterations", rclcpp::ParameterValue(1000000));
75 node->get_parameter(name +
".max_iterations", _max_iterations);
76 nav2_util::declare_parameter_if_not_declared(
77 node, name +
".max_on_approach_iterations", rclcpp::ParameterValue(1000));
78 node->get_parameter(name +
".max_on_approach_iterations", _max_on_approach_iterations);
79 nav2_util::declare_parameter_if_not_declared(
80 node, name +
".terminal_checking_interval", rclcpp::ParameterValue(5000));
81 node->get_parameter(name +
".terminal_checking_interval", _terminal_checking_interval);
82 nav2_util::declare_parameter_if_not_declared(
83 node, name +
".smooth_path", rclcpp::ParameterValue(
true));
84 node->get_parameter(name +
".smooth_path", smooth_path);
87 nav2_util::declare_parameter_if_not_declared(
88 node, name +
".lattice_filepath", rclcpp::ParameterValue(
89 ament_index_cpp::get_package_share_directory(
"nav2_smac_planner") +
90 "/sample_primitives/5cm_resolution/0.5m_turning_radius/ackermann/output.json"));
91 node->get_parameter(name +
".lattice_filepath", _search_info.lattice_filepath);
92 nav2_util::declare_parameter_if_not_declared(
93 node, name +
".cache_obstacle_heuristic", rclcpp::ParameterValue(
false));
94 node->get_parameter(name +
".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic);
95 nav2_util::declare_parameter_if_not_declared(
96 node, name +
".reverse_penalty", rclcpp::ParameterValue(2.0));
97 node->get_parameter(name +
".reverse_penalty", _search_info.reverse_penalty);
98 nav2_util::declare_parameter_if_not_declared(
99 node, name +
".change_penalty", rclcpp::ParameterValue(0.05));
100 node->get_parameter(name +
".change_penalty", _search_info.change_penalty);
101 nav2_util::declare_parameter_if_not_declared(
102 node, name +
".non_straight_penalty", rclcpp::ParameterValue(1.05));
103 node->get_parameter(name +
".non_straight_penalty", _search_info.non_straight_penalty);
104 nav2_util::declare_parameter_if_not_declared(
105 node, name +
".cost_penalty", rclcpp::ParameterValue(2.0));
106 node->get_parameter(name +
".cost_penalty", _search_info.cost_penalty);
107 nav2_util::declare_parameter_if_not_declared(
108 node, name +
".retrospective_penalty", rclcpp::ParameterValue(0.015));
109 node->get_parameter(name +
".retrospective_penalty", _search_info.retrospective_penalty);
110 nav2_util::declare_parameter_if_not_declared(
111 node, name +
".rotation_penalty", rclcpp::ParameterValue(5.0));
112 node->get_parameter(name +
".rotation_penalty", _search_info.rotation_penalty);
113 nav2_util::declare_parameter_if_not_declared(
114 node, name +
".analytic_expansion_ratio", rclcpp::ParameterValue(3.5));
115 node->get_parameter(name +
".analytic_expansion_ratio", _search_info.analytic_expansion_ratio);
116 nav2_util::declare_parameter_if_not_declared(
117 node, name +
".analytic_expansion_max_cost", rclcpp::ParameterValue(200.0));
119 name +
".analytic_expansion_max_cost", _search_info.analytic_expansion_max_cost);
120 nav2_util::declare_parameter_if_not_declared(
121 node, name +
".analytic_expansion_max_cost_override", rclcpp::ParameterValue(
false));
123 name +
".analytic_expansion_max_cost_override",
124 _search_info.analytic_expansion_max_cost_override);
125 nav2_util::declare_parameter_if_not_declared(
126 node, name +
".analytic_expansion_max_length", rclcpp::ParameterValue(3.0));
127 node->get_parameter(name +
".analytic_expansion_max_length", analytic_expansion_max_length_m);
128 _search_info.analytic_expansion_max_length =
131 nav2_util::declare_parameter_if_not_declared(
132 node, name +
".max_planning_time", rclcpp::ParameterValue(5.0));
133 node->get_parameter(name +
".max_planning_time", _max_planning_time);
134 nav2_util::declare_parameter_if_not_declared(
135 node, name +
".lookup_table_size", rclcpp::ParameterValue(20.0));
136 node->get_parameter(name +
".lookup_table_size", _lookup_table_size);
137 nav2_util::declare_parameter_if_not_declared(
138 node, name +
".allow_reverse_expansion", rclcpp::ParameterValue(
false));
139 node->get_parameter(name +
".allow_reverse_expansion", _search_info.allow_reverse_expansion);
140 nav2_util::declare_parameter_if_not_declared(
141 node, name +
".debug_visualizations", rclcpp::ParameterValue(
false));
142 node->get_parameter(name +
".debug_visualizations", _debug_visualizations);
145 _search_info.minimum_turning_radius =
147 _motion_model = MotionModel::STATE_LATTICE;
149 if (_max_on_approach_iterations <= 0) {
151 _logger,
"On approach iteration selected as <= 0, "
152 "disabling tolerance and on approach iterations.");
153 _max_on_approach_iterations = std::numeric_limits<int>::max();
156 if (_max_iterations <= 0) {
158 _logger,
"maximum iteration selected as <= 0, "
159 "disabling maximum iterations.");
160 _max_iterations = std::numeric_limits<int>::max();
163 float lookup_table_dim =
164 static_cast<float>(_lookup_table_size) /
168 lookup_table_dim =
static_cast<float>(
static_cast<int>(lookup_table_dim));
171 if (
static_cast<int>(lookup_table_dim) % 2 == 0) {
174 "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
176 lookup_table_dim += 1.0;
188 costmap_ros->getRobotFootprint(),
189 costmap_ros->getUseRadius(),
190 findCircumscribedCost(costmap_ros));
193 _a_star = std::make_unique<AStarAlgorithm<NodeLattice>>(_motion_model, _search_info);
197 _max_on_approach_iterations,
198 _terminal_checking_interval,
201 _metadata.number_of_headings);
206 params.
get(node, name);
207 _smoother = std::make_unique<Smoother>(params);
208 _smoother->initialize(_metadata.min_turning_radius);
211 _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>(
"unsmoothed_plan", 1);
213 if (_debug_visualizations) {
214 _expansions_publisher = node->create_publisher<geometry_msgs::msg::PoseArray>(
"expansions", 1);
215 _planned_footprints_publisher = node->create_publisher<visualization_msgs::msg::MarkerArray>(
216 "planned_footprints", 1);
217 _smoothed_footprints_publisher =
218 node->create_publisher<visualization_msgs::msg::MarkerArray>(
219 "smoothed_footprints", 1);
223 _logger,
"Configured plugin %s of type SmacPlannerLattice with "
224 "maximum iterations %i, max on approach iterations %i, "
225 "and %s. Tolerance %.2f. Using motion model: %s. State lattice file: %s.",
226 _name.c_str(), _max_iterations, _max_on_approach_iterations,
227 _allow_unknown ?
"allowing unknown traversal" :
"not allowing unknown traversal",
228 _tolerance, toString(_motion_model).c_str(), _search_info.lattice_filepath.c_str());
234 _logger,
"Activating plugin %s of type SmacPlannerLattice",
236 _raw_plan_publisher->on_activate();
237 if (_debug_visualizations) {
238 _expansions_publisher->on_activate();
239 _planned_footprints_publisher->on_activate();
240 _smoothed_footprints_publisher->on_activate();
242 auto node = _node.lock();
244 _dyn_params_handler = node->add_on_set_parameters_callback(
251 _logger,
"Deactivating plugin %s of type SmacPlannerLattice",
253 _raw_plan_publisher->on_deactivate();
254 if (_debug_visualizations) {
255 _expansions_publisher->on_deactivate();
256 _planned_footprints_publisher->on_deactivate();
257 _smoothed_footprints_publisher->on_deactivate();
260 auto node = _node.lock();
261 if (_dyn_params_handler && node) {
262 node->remove_on_set_parameters_callback(_dyn_params_handler.get());
264 _dyn_params_handler.reset();
270 _logger,
"Cleaning up plugin %s of type SmacPlannerLattice",
275 _raw_plan_publisher.reset();
276 if (_debug_visualizations) {
277 _expansions_publisher.reset();
278 _planned_footprints_publisher.reset();
279 _smoothed_footprints_publisher.reset();
284 const geometry_msgs::msg::PoseStamped & start,
285 const geometry_msgs::msg::PoseStamped & goal,
286 std::function<
bool()> cancel_checker)
288 std::lock_guard<std::mutex> lock_reinit(_mutex);
289 steady_clock::time_point a = steady_clock::now();
291 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
295 _costmap_ros->getRobotFootprint(),
296 _costmap_ros->getUseRadius(),
297 findCircumscribedCost(_costmap_ros));
298 _a_star->setCollisionChecker(&_collision_checker);
301 float mx_start, my_start, mx_goal, my_goal;
303 start.pose.position.x,
304 start.pose.position.y,
309 "Start Coordinates of(" + std::to_string(start.pose.position.x) +
", " +
310 std::to_string(start.pose.position.y) +
") was outside bounds");
314 NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(start.pose.orientation)));
318 goal.pose.position.x,
319 goal.pose.position.y,
324 "Goal Coordinates of(" + std::to_string(goal.pose.position.x) +
", " +
325 std::to_string(goal.pose.position.y) +
") was outside bounds");
329 NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(goal.pose.orientation)));
332 nav_msgs::msg::Path plan;
333 plan.header.stamp = _clock->now();
334 plan.header.frame_id = _global_frame;
335 geometry_msgs::msg::PoseStamped pose;
336 pose.header = plan.header;
337 pose.pose.position.z = 0.0;
338 pose.pose.orientation.x = 0.0;
339 pose.pose.orientation.y = 0.0;
340 pose.pose.orientation.z = 0.0;
341 pose.pose.orientation.w = 1.0;
344 if (std::floor(mx_start) == std::floor(mx_goal) &&
345 std::floor(my_start) == std::floor(my_goal))
347 pose.pose = start.pose;
348 pose.pose.orientation = goal.pose.orientation;
349 plan.poses.push_back(pose);
352 if (_raw_plan_publisher->get_subscription_count() > 0) {
353 _raw_plan_publisher->publish(plan);
360 NodeLattice::CoordinateVector path;
361 int num_iterations = 0;
363 std::unique_ptr<std::vector<std::tuple<float, float, float>>> expansions =
nullptr;
364 if (_debug_visualizations) {
365 expansions = std::make_unique<std::vector<std::tuple<float, float, float>>>();
369 if (!_a_star->createPath(
370 path, num_iterations,
371 _tolerance /
static_cast<float>(_costmap->
getResolution()), cancel_checker, expansions.get()))
373 if (_debug_visualizations) {
374 auto now = _clock->now();
375 geometry_msgs::msg::PoseArray msg;
376 geometry_msgs::msg::Pose msg_pose;
377 msg.header.stamp = now;
378 msg.header.frame_id = _global_frame;
379 for (
auto & e : *expansions) {
380 msg_pose.position.x = std::get<0>(e);
381 msg_pose.position.y = std::get<1>(e);
382 msg_pose.orientation = getWorldOrientation(std::get<2>(e));
383 msg.poses.push_back(msg_pose);
385 _expansions_publisher->publish(msg);
389 if (num_iterations == 1) {
393 if (num_iterations < _a_star->getMaxIterations()) {
401 plan.poses.reserve(path.size());
402 geometry_msgs::msg::PoseStamped last_pose = pose;
403 for (
int i = path.size() - 1; i >= 0; --i) {
404 pose.pose = getWorldCoords(path[i].x, path[i].y, _costmap);
405 pose.pose.orientation = getWorldOrientation(path[i].theta);
406 if (fabs(pose.pose.position.x - last_pose.pose.position.x) < 1e-4 &&
407 fabs(pose.pose.position.y - last_pose.pose.position.y) < 1e-4 &&
408 fabs(tf2::getYaw(pose.pose.orientation) - tf2::getYaw(last_pose.pose.orientation)) < 1e-4)
412 "Removed a path from the path due to replication. "
413 "Make sure your minimum control set does not contain duplicate values!");
417 plan.poses.push_back(pose);
421 if (_raw_plan_publisher->get_subscription_count() > 0) {
422 _raw_plan_publisher->publish(plan);
425 if (_debug_visualizations) {
426 auto now = _clock->now();
428 geometry_msgs::msg::PoseArray msg;
429 geometry_msgs::msg::Pose msg_pose;
430 msg.header.stamp = now;
431 msg.header.frame_id = _global_frame;
432 for (
auto & e : *expansions) {
433 msg_pose.position.x = std::get<0>(e);
434 msg_pose.position.y = std::get<1>(e);
435 msg_pose.orientation = getWorldOrientation(std::get<2>(e));
436 msg.poses.push_back(msg_pose);
438 _expansions_publisher->publish(msg);
440 if (_planned_footprints_publisher->get_subscription_count() > 0) {
442 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
443 visualization_msgs::msg::Marker clear_all_marker;
444 clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
445 marker_array->markers.push_back(clear_all_marker);
446 _planned_footprints_publisher->publish(std::move(marker_array));
449 marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
450 for (
size_t i = 0; i < plan.poses.size(); i++) {
451 const std::vector<geometry_msgs::msg::Point> edge =
452 transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
453 marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
455 _planned_footprints_publisher->publish(std::move(marker_array));
460 steady_clock::time_point b = steady_clock::now();
461 duration<double> time_span = duration_cast<duration<double>>(b - a);
462 double time_remaining = _max_planning_time -
static_cast<double>(time_span.count());
464 #ifdef BENCHMARK_TESTING
465 std::cout <<
"It took " << time_span.count() * 1000 <<
466 " milliseconds with " << num_iterations <<
" iterations." << std::endl;
470 if (_smoother && num_iterations > 1) {
471 _smoother->smooth(plan, _costmap, time_remaining);
474 #ifdef BENCHMARK_TESTING
475 steady_clock::time_point c = steady_clock::now();
476 duration<double> time_span2 = duration_cast<duration<double>>(c - b);
477 std::cout <<
"It took " << time_span2.count() * 1000 <<
478 " milliseconds to smooth path." << std::endl;
481 if (_debug_visualizations) {
482 if (_smoothed_footprints_publisher->get_subscription_count() > 0) {
484 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
485 visualization_msgs::msg::Marker clear_all_marker;
486 clear_all_marker.action = visualization_msgs::msg::Marker::DELETEALL;
487 marker_array->markers.push_back(clear_all_marker);
488 _smoothed_footprints_publisher->publish(std::move(marker_array));
491 marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
492 auto now = _clock->now();
493 for (
size_t i = 0; i < plan.poses.size(); i++) {
494 const std::vector<geometry_msgs::msg::Point> edge =
495 transformFootprintToEdges(plan.poses[i].pose, _costmap_ros->getRobotFootprint());
496 marker_array->markers.push_back(createMarker(edge, i, _global_frame, now));
498 _smoothed_footprints_publisher->publish(std::move(marker_array));
505 rcl_interfaces::msg::SetParametersResult
508 rcl_interfaces::msg::SetParametersResult result;
509 std::lock_guard<std::mutex> lock_reinit(_mutex);
511 bool reinit_a_star =
false;
512 bool reinit_smoother =
false;
514 for (
auto parameter : parameters) {
515 const auto & type = parameter.get_type();
516 const auto & name = parameter.get_name();
518 if (type == ParameterType::PARAMETER_DOUBLE) {
519 if (name == _name +
".max_planning_time") {
520 reinit_a_star =
true;
521 _max_planning_time = parameter.as_double();
522 }
else if (name == _name +
".tolerance") {
523 _tolerance =
static_cast<float>(parameter.as_double());
524 }
else if (name == _name +
".lookup_table_size") {
525 reinit_a_star =
true;
526 _lookup_table_size = parameter.as_double();
527 }
else if (name == _name +
".reverse_penalty") {
528 reinit_a_star =
true;
529 _search_info.reverse_penalty =
static_cast<float>(parameter.as_double());
530 }
else if (name == _name +
".change_penalty") {
531 reinit_a_star =
true;
532 _search_info.change_penalty =
static_cast<float>(parameter.as_double());
533 }
else if (name == _name +
".non_straight_penalty") {
534 reinit_a_star =
true;
535 _search_info.non_straight_penalty =
static_cast<float>(parameter.as_double());
536 }
else if (name == _name +
".cost_penalty") {
537 reinit_a_star =
true;
538 _search_info.cost_penalty =
static_cast<float>(parameter.as_double());
539 }
else if (name == _name +
".rotation_penalty") {
540 reinit_a_star =
true;
541 _search_info.rotation_penalty =
static_cast<float>(parameter.as_double());
542 }
else if (name == _name +
".analytic_expansion_ratio") {
543 reinit_a_star =
true;
544 _search_info.analytic_expansion_ratio =
static_cast<float>(parameter.as_double());
545 }
else if (name == _name +
".analytic_expansion_max_length") {
546 reinit_a_star =
true;
547 _search_info.analytic_expansion_max_length =
548 static_cast<float>(parameter.as_double()) / _costmap->
getResolution();
549 }
else if (name == _name +
".analytic_expansion_max_cost") {
550 reinit_a_star =
true;
551 _search_info.analytic_expansion_max_cost =
static_cast<float>(parameter.as_double());
553 }
else if (type == ParameterType::PARAMETER_BOOL) {
554 if (name == _name +
".allow_unknown") {
555 reinit_a_star =
true;
556 _allow_unknown = parameter.as_bool();
557 }
else if (name == _name +
".cache_obstacle_heuristic") {
558 reinit_a_star =
true;
559 _search_info.cache_obstacle_heuristic = parameter.as_bool();
560 }
else if (name == _name +
".allow_reverse_expansion") {
561 reinit_a_star =
true;
562 _search_info.allow_reverse_expansion = parameter.as_bool();
563 }
else if (name == _name +
".smooth_path") {
564 if (parameter.as_bool()) {
565 reinit_smoother =
true;
569 }
else if (name == _name +
".analytic_expansion_max_cost_override") {
570 _search_info.analytic_expansion_max_cost_override = parameter.as_bool();
571 reinit_a_star =
true;
573 }
else if (type == ParameterType::PARAMETER_INTEGER) {
574 if (name == _name +
".max_iterations") {
575 reinit_a_star =
true;
576 _max_iterations = parameter.as_int();
577 if (_max_iterations <= 0) {
579 _logger,
"maximum iteration selected as <= 0, "
580 "disabling maximum iterations.");
581 _max_iterations = std::numeric_limits<int>::max();
583 }
else if (name == _name +
".max_on_approach_iterations") {
584 reinit_a_star =
true;
585 _max_on_approach_iterations = parameter.as_int();
586 if (_max_on_approach_iterations <= 0) {
588 _logger,
"On approach iteration selected as <= 0, "
589 "disabling tolerance and on approach iterations.");
590 _max_on_approach_iterations = std::numeric_limits<int>::max();
592 }
else if (name == _name +
".terminal_checking_interval") {
593 reinit_a_star =
true;
594 _terminal_checking_interval = parameter.as_int();
596 }
else if (type == ParameterType::PARAMETER_STRING) {
597 if (name == _name +
".lattice_filepath") {
598 reinit_a_star =
true;
600 reinit_smoother =
true;
602 _search_info.lattice_filepath = parameter.as_string();
604 _search_info.minimum_turning_radius =
611 if (reinit_a_star || reinit_smoother) {
613 _search_info.minimum_turning_radius =
615 float lookup_table_dim =
616 static_cast<float>(_lookup_table_size) /
620 lookup_table_dim =
static_cast<float>(
static_cast<int>(lookup_table_dim));
623 if (
static_cast<int>(lookup_table_dim) % 2 == 0) {
626 "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd",
628 lookup_table_dim += 1.0;
632 if (reinit_smoother) {
633 auto node = _node.lock();
635 params.
get(node, _name);
636 _smoother = std::make_unique<Smoother>(params);
637 _smoother->initialize(_metadata.min_turning_radius);
642 _a_star = std::make_unique<AStarAlgorithm<NodeLattice>>(_motion_model, _search_info);
646 _max_on_approach_iterations,
647 _terminal_checking_interval,
650 _metadata.number_of_headings);
654 result.successful =
true;
660 #include "pluginlib/class_list_macros.hpp"
Abstract interface for global planners to adhere to with pluginlib.
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 deactivate() override
Deactivate lifecycle node.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Configuring plugin.
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.
~SmacPlannerLattice()
destructor
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
void cleanup() override
Cleanup lifecycle node.
SmacPlannerLattice()
constructor
void activate() override
Activate lifecycle node.
static LatticeMetadata getLatticeMetadata(const std::string &lattice_filepath)
Get file metadata needed.
Parameters for the smoother cost function.
void get(std::shared_ptr< rclcpp_lifecycle::LifecycleNode > node, const std::string &name)
Get params from ROS parameter.