21 #include "nav2_smac_planner/smac_planner_2d.hpp"
22 #include "nav2_util/geometry_utils.hpp"
26 namespace nav2_smac_planner
28 using namespace std::chrono;
29 using rcl_interfaces::msg::ParameterType;
30 using std::placeholders::_1;
34 _collision_checker(nullptr, 1, nullptr),
37 _costmap_downsampler(nullptr)
44 _logger,
"Destroying plugin %s of type SmacPlanner2D",
49 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
50 std::string name, std::shared_ptr<tf2_ros::Buffer>,
51 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
54 auto node = parent.lock();
55 _logger = node->get_logger();
56 _clock = node->get_clock();
57 _costmap = costmap_ros->getCostmap();
59 _global_frame = costmap_ros->getGlobalFrameID();
61 RCLCPP_INFO(_logger,
"Configuring %s of type SmacPlanner2D", name.c_str());
64 nav2_util::declare_parameter_if_not_declared(
65 node, name +
".tolerance", rclcpp::ParameterValue(0.125));
66 _tolerance =
static_cast<float>(node->get_parameter(name +
".tolerance").as_double());
67 nav2_util::declare_parameter_if_not_declared(
68 node, name +
".downsample_costmap", rclcpp::ParameterValue(
false));
69 node->get_parameter(name +
".downsample_costmap", _downsample_costmap);
70 nav2_util::declare_parameter_if_not_declared(
71 node, name +
".downsampling_factor", rclcpp::ParameterValue(1));
72 node->get_parameter(name +
".downsampling_factor", _downsampling_factor);
73 nav2_util::declare_parameter_if_not_declared(
74 node, name +
".cost_travel_multiplier", rclcpp::ParameterValue(1.0));
75 node->get_parameter(name +
".cost_travel_multiplier", _search_info.cost_penalty);
77 nav2_util::declare_parameter_if_not_declared(
78 node, name +
".allow_unknown", rclcpp::ParameterValue(
true));
79 node->get_parameter(name +
".allow_unknown", _allow_unknown);
80 nav2_util::declare_parameter_if_not_declared(
81 node, name +
".max_iterations", rclcpp::ParameterValue(1000000));
82 node->get_parameter(name +
".max_iterations", _max_iterations);
83 nav2_util::declare_parameter_if_not_declared(
84 node, name +
".max_on_approach_iterations", rclcpp::ParameterValue(1000));
85 node->get_parameter(name +
".max_on_approach_iterations", _max_on_approach_iterations);
86 nav2_util::declare_parameter_if_not_declared(
87 node, name +
".terminal_checking_interval", rclcpp::ParameterValue(5000));
88 node->get_parameter(name +
".terminal_checking_interval", _terminal_checking_interval);
89 nav2_util::declare_parameter_if_not_declared(
90 node, name +
".use_final_approach_orientation", rclcpp::ParameterValue(
false));
91 node->get_parameter(name +
".use_final_approach_orientation", _use_final_approach_orientation);
93 nav2_util::declare_parameter_if_not_declared(
94 node, name +
".max_planning_time", rclcpp::ParameterValue(2.0));
95 node->get_parameter(name +
".max_planning_time", _max_planning_time);
97 _motion_model = MotionModel::TWOD;
99 if (_max_on_approach_iterations <= 0) {
101 _logger,
"On approach iteration selected as <= 0, "
102 "disabling tolerance and on approach iterations.");
103 _max_on_approach_iterations = std::numeric_limits<int>::max();
106 if (_max_iterations <= 0) {
108 _logger,
"maximum iteration selected as <= 0, "
109 "disabling maximum iterations.");
110 _max_iterations = std::numeric_limits<int>::max();
116 costmap_ros->getRobotFootprint(),
121 _a_star = std::make_unique<AStarAlgorithm<Node2D>>(_motion_model, _search_info);
125 _max_on_approach_iterations,
126 _terminal_checking_interval,
133 params.
get(node, name);
134 params.holonomic_ =
true;
135 _smoother = std::make_unique<Smoother>(params);
136 _smoother->initialize(1e-50 );
139 if (_downsample_costmap && _downsampling_factor > 1) {
140 std::string topic_name =
"downsampled_costmap";
141 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
142 _costmap_downsampler->on_configure(
143 node, _global_frame, topic_name, _costmap, _downsampling_factor);
146 _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>(
"unsmoothed_plan", 1);
149 _logger,
"Configured plugin %s of type SmacPlanner2D with "
150 "tolerance %.2f, maximum iterations %i, "
151 "max on approach iterations %i, and %s.",
152 _name.c_str(), _tolerance, _max_iterations, _max_on_approach_iterations,
153 _allow_unknown ?
"allowing unknown traversal" :
"not allowing unknown traversal");
159 _logger,
"Activating plugin %s of type SmacPlanner2D",
161 _raw_plan_publisher->on_activate();
162 if (_costmap_downsampler) {
163 _costmap_downsampler->on_activate();
165 auto node = _node.lock();
167 _dyn_params_handler = node->add_on_set_parameters_callback(
174 _logger,
"Deactivating plugin %s of type SmacPlanner2D",
176 _raw_plan_publisher->on_deactivate();
177 if (_costmap_downsampler) {
178 _costmap_downsampler->on_deactivate();
181 auto node = _node.lock();
182 if (_dyn_params_handler && node) {
183 node->remove_on_set_parameters_callback(_dyn_params_handler.get());
185 _dyn_params_handler.reset();
191 _logger,
"Cleaning up plugin %s of type SmacPlanner2D",
195 if (_costmap_downsampler) {
196 _costmap_downsampler->on_cleanup();
197 _costmap_downsampler.reset();
199 _raw_plan_publisher.reset();
203 const geometry_msgs::msg::PoseStamped & start,
204 const geometry_msgs::msg::PoseStamped & goal,
205 std::function<
bool()> cancel_checker)
207 std::lock_guard<std::mutex> lock_reinit(_mutex);
208 steady_clock::time_point a = steady_clock::now();
210 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
214 if (_costmap_downsampler) {
215 costmap = _costmap_downsampler->downsample(_downsampling_factor);
220 _a_star->setCollisionChecker(&_collision_checker);
223 float mx_start, my_start, mx_goal, my_goal;
225 start.pose.position.x,
226 start.pose.position.y,
231 "Start Coordinates of(" + std::to_string(start.pose.position.x) +
", " +
232 std::to_string(start.pose.position.y) +
") was outside bounds");
234 _a_star->setStart(mx_start, my_start, 0);
238 goal.pose.position.x,
239 goal.pose.position.y,
244 "Goal Coordinates of(" + std::to_string(goal.pose.position.x) +
", " +
245 std::to_string(goal.pose.position.y) +
") was outside bounds");
247 _a_star->setGoal(mx_goal, my_goal, 0);
250 nav_msgs::msg::Path plan;
251 plan.header.stamp = _clock->now();
252 plan.header.frame_id = _global_frame;
253 geometry_msgs::msg::PoseStamped pose;
254 pose.header = plan.header;
255 pose.pose.position.z = 0.0;
256 pose.pose.orientation.x = 0.0;
257 pose.pose.orientation.y = 0.0;
258 pose.pose.orientation.z = 0.0;
259 pose.pose.orientation.w = 1.0;
262 if (std::floor(mx_start) == std::floor(mx_goal) && std::floor(my_start) == std::floor(my_goal)) {
263 pose.pose = start.pose;
267 if (start.pose.orientation != goal.pose.orientation && !_use_final_approach_orientation) {
268 pose.pose.orientation = goal.pose.orientation;
270 plan.poses.push_back(pose);
273 if (_raw_plan_publisher->get_subscription_count() > 0) {
274 _raw_plan_publisher->publish(plan);
281 Node2D::CoordinateVector path;
282 int num_iterations = 0;
284 if (!_a_star->createPath(
285 path, num_iterations,
286 _tolerance /
static_cast<float>(costmap->
getResolution()), cancel_checker))
289 if (num_iterations == 1) {
293 if (num_iterations < _a_star->getMaxIterations()) {
301 plan.poses.reserve(path.size());
302 for (
int i = path.size() - 1; i >= 0; --i) {
303 pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
304 plan.poses.push_back(pose);
308 if (_raw_plan_publisher->get_subscription_count() > 0) {
309 _raw_plan_publisher->publish(plan);
313 steady_clock::time_point b = steady_clock::now();
314 duration<double> time_span = duration_cast<duration<double>>(b - a);
315 double time_remaining = _max_planning_time -
static_cast<double>(time_span.count());
317 #ifdef BENCHMARK_TESTING
318 std::cout <<
"It took " << time_span.count() * 1000 <<
319 " milliseconds with " << num_iterations <<
" iterations." << std::endl;
323 _smoother->smooth(plan, costmap, time_remaining);
330 size_t plan_size = plan.poses.size();
331 if (_use_final_approach_orientation) {
332 if (plan_size == 1) {
333 plan.poses.back().pose.orientation = start.pose.orientation;
334 }
else if (plan_size > 1) {
335 double dx, dy, theta;
336 auto last_pose = plan.poses.back().pose.position;
337 auto approach_pose = plan.poses[plan_size - 2].pose.position;
338 dx = last_pose.x - approach_pose.x;
339 dy = last_pose.y - approach_pose.y;
340 theta = atan2(dy, dx);
341 plan.poses.back().pose.orientation =
342 nav2_util::geometry_utils::orientationAroundZAxis(theta);
344 }
else if (plan_size > 0) {
345 plan.poses.back().pose.orientation = goal.pose.orientation;
351 rcl_interfaces::msg::SetParametersResult
354 rcl_interfaces::msg::SetParametersResult result;
355 std::lock_guard<std::mutex> lock_reinit(_mutex);
357 bool reinit_a_star =
false;
358 bool reinit_downsampler =
false;
360 for (
auto parameter : parameters) {
361 const auto & type = parameter.get_type();
362 const auto & name = parameter.get_name();
364 if (type == ParameterType::PARAMETER_DOUBLE) {
365 if (name == _name +
".tolerance") {
366 _tolerance =
static_cast<float>(parameter.as_double());
367 }
else if (name == _name +
".cost_travel_multiplier") {
368 reinit_a_star =
true;
369 _search_info.cost_penalty = parameter.as_double();
370 }
else if (name == _name +
".max_planning_time") {
371 reinit_a_star =
true;
372 _max_planning_time = parameter.as_double();
374 }
else if (type == ParameterType::PARAMETER_BOOL) {
375 if (name == _name +
".downsample_costmap") {
376 reinit_downsampler =
true;
377 _downsample_costmap = parameter.as_bool();
378 }
else if (name == _name +
".allow_unknown") {
379 reinit_a_star =
true;
380 _allow_unknown = parameter.as_bool();
381 }
else if (name == _name +
".use_final_approach_orientation") {
382 _use_final_approach_orientation = parameter.as_bool();
384 }
else if (type == ParameterType::PARAMETER_INTEGER) {
385 if (name == _name +
".downsampling_factor") {
386 reinit_downsampler =
true;
387 _downsampling_factor = parameter.as_int();
388 }
else if (name == _name +
".max_iterations") {
389 reinit_a_star =
true;
390 _max_iterations = parameter.as_int();
391 if (_max_iterations <= 0) {
393 _logger,
"maximum iteration selected as <= 0, "
394 "disabling maximum iterations.");
395 _max_iterations = std::numeric_limits<int>::max();
397 }
else if (name == _name +
".max_on_approach_iterations") {
398 reinit_a_star =
true;
399 _max_on_approach_iterations = parameter.as_int();
400 if (_max_on_approach_iterations <= 0) {
402 _logger,
"On approach iteration selected as <= 0, "
403 "disabling tolerance and on approach iterations.");
404 _max_on_approach_iterations = std::numeric_limits<int>::max();
406 }
else if (name == _name +
".terminal_checking_interval") {
407 reinit_a_star =
true;
408 _terminal_checking_interval = parameter.as_int();
414 if (reinit_a_star || reinit_downsampler) {
417 _a_star = std::make_unique<AStarAlgorithm<Node2D>>(_motion_model, _search_info);
421 _max_on_approach_iterations,
422 _terminal_checking_interval,
429 if (reinit_downsampler) {
430 if (_downsample_costmap && _downsampling_factor > 1) {
431 auto node = _node.lock();
432 std::string topic_name =
"downsampled_costmap";
433 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
434 _costmap_downsampler->on_configure(
435 node, _global_frame, topic_name, _costmap, _downsampling_factor);
439 result.successful =
true;
445 #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...
void activate() override
Activate lifecycle node.
SmacPlanner2D()
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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
~SmacPlanner2D()
destructor
void cleanup() override
Cleanup lifecycle node.
void deactivate() override
Deactivate lifecycle node.
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.
Parameters for the smoother cost function.
void get(std::shared_ptr< rclcpp_lifecycle::LifecycleNode > node, const std::string &name)
Get params from ROS parameter.