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 +
".use_final_approach_orientation", rclcpp::ParameterValue(
false));
88 node->get_parameter(name +
".use_final_approach_orientation", _use_final_approach_orientation);
90 nav2_util::declare_parameter_if_not_declared(
91 node, name +
".max_planning_time", rclcpp::ParameterValue(2.0));
92 node->get_parameter(name +
".max_planning_time", _max_planning_time);
94 _motion_model = MotionModel::TWOD;
96 if (_max_on_approach_iterations <= 0) {
98 _logger,
"On approach iteration selected as <= 0, "
99 "disabling tolerance and on approach iterations.");
100 _max_on_approach_iterations = std::numeric_limits<int>::max();
103 if (_max_iterations <= 0) {
105 _logger,
"maximum iteration selected as <= 0, "
106 "disabling maximum iterations.");
107 _max_iterations = std::numeric_limits<int>::max();
113 costmap_ros->getRobotFootprint(),
118 _a_star = std::make_unique<AStarAlgorithm<Node2D>>(_motion_model, _search_info);
122 _max_on_approach_iterations,
129 params.
get(node, name);
130 params.holonomic_ =
true;
131 _smoother = std::make_unique<Smoother>(params);
132 _smoother->initialize(1e-50 );
135 if (_downsample_costmap && _downsampling_factor > 1) {
136 std::string topic_name =
"downsampled_costmap";
137 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
138 _costmap_downsampler->on_configure(
139 node, _global_frame, topic_name, _costmap, _downsampling_factor);
142 _raw_plan_publisher = node->create_publisher<nav_msgs::msg::Path>(
"unsmoothed_plan", 1);
145 _logger,
"Configured plugin %s of type SmacPlanner2D with "
146 "tolerance %.2f, maximum iterations %i, "
147 "max on approach iterations %i, and %s.",
148 _name.c_str(), _tolerance, _max_iterations, _max_on_approach_iterations,
149 _allow_unknown ?
"allowing unknown traversal" :
"not allowing unknown traversal");
155 _logger,
"Activating plugin %s of type SmacPlanner2D",
157 _raw_plan_publisher->on_activate();
158 if (_costmap_downsampler) {
159 _costmap_downsampler->on_activate();
161 auto node = _node.lock();
163 _dyn_params_handler = node->add_on_set_parameters_callback(
170 _logger,
"Deactivating plugin %s of type SmacPlanner2D",
172 _raw_plan_publisher->on_deactivate();
173 if (_costmap_downsampler) {
174 _costmap_downsampler->on_deactivate();
176 _dyn_params_handler.reset();
182 _logger,
"Cleaning up plugin %s of type SmacPlanner2D",
186 if (_costmap_downsampler) {
187 _costmap_downsampler->on_cleanup();
188 _costmap_downsampler.reset();
190 _raw_plan_publisher.reset();
194 const geometry_msgs::msg::PoseStamped & start,
195 const geometry_msgs::msg::PoseStamped & goal)
197 std::lock_guard<std::mutex> lock_reinit(_mutex);
198 steady_clock::time_point a = steady_clock::now();
200 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(_costmap->getMutex()));
204 if (_costmap_downsampler) {
205 costmap = _costmap_downsampler->downsample(_downsampling_factor);
210 _a_star->setCollisionChecker(&_collision_checker);
213 unsigned int mx_start, my_start, mx_goal, my_goal;
214 costmap->
worldToMap(start.pose.position.x, start.pose.position.y, mx_start, my_start);
215 _a_star->setStart(mx_start, my_start, 0);
218 costmap->
worldToMap(goal.pose.position.x, goal.pose.position.y, mx_goal, my_goal);
219 _a_star->setGoal(mx_goal, my_goal, 0);
222 nav_msgs::msg::Path plan;
223 plan.header.stamp = _clock->now();
224 plan.header.frame_id = _global_frame;
225 geometry_msgs::msg::PoseStamped pose;
226 pose.header = plan.header;
227 pose.pose.position.z = 0.0;
228 pose.pose.orientation.x = 0.0;
229 pose.pose.orientation.y = 0.0;
230 pose.pose.orientation.z = 0.0;
231 pose.pose.orientation.w = 1.0;
234 if (mx_start == mx_goal && my_start == my_goal) {
235 if (costmap->
getCost(mx_start, my_start) == nav2_costmap_2d::LETHAL_OBSTACLE) {
236 RCLCPP_WARN(_logger,
"Failed to create a unique pose path because of obstacles");
239 pose.pose = start.pose;
243 if (start.pose.orientation != goal.pose.orientation && !_use_final_approach_orientation) {
244 pose.pose.orientation = goal.pose.orientation;
246 plan.poses.push_back(pose);
251 Node2D::CoordinateVector path;
252 int num_iterations = 0;
255 if (!_a_star->createPath(
256 path, num_iterations, _tolerance /
static_cast<float>(costmap->
getResolution())))
258 if (num_iterations < _a_star->getMaxIterations()) {
259 error = std::string(
"no valid path found");
261 error = std::string(
"exceeded maximum iterations");
264 }
catch (
const std::runtime_error & e) {
265 error =
"invalid use: ";
269 if (!error.empty()) {
272 "%s: failed to create plan, %s.",
273 _name.c_str(), error.c_str());
278 plan.poses.reserve(path.size());
279 for (
int i = path.size() - 1; i >= 0; --i) {
280 pose.pose = getWorldCoords(path[i].x, path[i].y, costmap);
281 plan.poses.push_back(pose);
285 if (_raw_plan_publisher->get_subscription_count() > 0) {
286 _raw_plan_publisher->publish(plan);
290 steady_clock::time_point b = steady_clock::now();
291 duration<double> time_span = duration_cast<duration<double>>(b - a);
292 double time_remaining = _max_planning_time -
static_cast<double>(time_span.count());
294 #ifdef BENCHMARK_TESTING
295 std::cout <<
"It took " << time_span.count() * 1000 <<
296 " milliseconds with " << num_iterations <<
" iterations." << std::endl;
300 _smoother->smooth(plan, costmap, time_remaining);
307 size_t plan_size = plan.poses.size();
308 if (_use_final_approach_orientation) {
309 if (plan_size == 1) {
310 plan.poses.back().pose.orientation = start.pose.orientation;
311 }
else if (plan_size > 1) {
312 double dx, dy, theta;
313 auto last_pose = plan.poses.back().pose.position;
314 auto approach_pose = plan.poses[plan_size - 2].pose.position;
315 dx = last_pose.x - approach_pose.x;
316 dy = last_pose.y - approach_pose.y;
317 theta = atan2(dy, dx);
318 plan.poses.back().pose.orientation =
319 nav2_util::geometry_utils::orientationAroundZAxis(theta);
321 }
else if (plan_size > 0) {
322 plan.poses.back().pose.orientation = goal.pose.orientation;
328 rcl_interfaces::msg::SetParametersResult
331 rcl_interfaces::msg::SetParametersResult result;
332 std::lock_guard<std::mutex> lock_reinit(_mutex);
334 bool reinit_a_star =
false;
335 bool reinit_downsampler =
false;
337 for (
auto parameter : parameters) {
338 const auto & type = parameter.get_type();
339 const auto & name = parameter.get_name();
341 if (type == ParameterType::PARAMETER_DOUBLE) {
342 if (name == _name +
".tolerance") {
343 _tolerance =
static_cast<float>(parameter.as_double());
344 }
else if (name == _name +
".cost_travel_multiplier") {
345 reinit_a_star =
true;
346 _search_info.cost_penalty = parameter.as_double();
347 }
else if (name == _name +
".max_planning_time") {
348 reinit_a_star =
true;
349 _max_planning_time = parameter.as_double();
351 }
else if (type == ParameterType::PARAMETER_BOOL) {
352 if (name == _name +
".downsample_costmap") {
353 reinit_downsampler =
true;
354 _downsample_costmap = parameter.as_bool();
355 }
else if (name == _name +
".allow_unknown") {
356 reinit_a_star =
true;
357 _allow_unknown = parameter.as_bool();
358 }
else if (name == _name +
".use_final_approach_orientation") {
359 _use_final_approach_orientation = parameter.as_bool();
361 }
else if (type == ParameterType::PARAMETER_INTEGER) {
362 if (name == _name +
".downsampling_factor") {
363 reinit_downsampler =
true;
364 _downsampling_factor = parameter.as_int();
365 }
else if (name == _name +
".max_iterations") {
366 reinit_a_star =
true;
367 _max_iterations = parameter.as_int();
368 if (_max_iterations <= 0) {
370 _logger,
"maximum iteration selected as <= 0, "
371 "disabling maximum iterations.");
372 _max_iterations = std::numeric_limits<int>::max();
374 }
else if (name == _name +
".max_on_approach_iterations") {
375 reinit_a_star =
true;
376 _max_on_approach_iterations = parameter.as_int();
377 if (_max_on_approach_iterations <= 0) {
379 _logger,
"On approach iteration selected as <= 0, "
380 "disabling tolerance and on approach iterations.");
381 _max_on_approach_iterations = std::numeric_limits<int>::max();
388 if (reinit_a_star || reinit_downsampler) {
391 _a_star = std::make_unique<AStarAlgorithm<Node2D>>(_motion_model, _search_info);
395 _max_on_approach_iterations,
402 if (reinit_downsampler) {
403 if (_downsample_costmap && _downsampling_factor > 1) {
404 auto node = _node.lock();
405 std::string topic_name =
"downsampled_costmap";
406 _costmap_downsampler = std::make_unique<CostmapDownsampler>();
407 _costmap_downsampler->on_configure(
408 node, _global_frame, topic_name, _costmap, _downsampling_factor);
412 result.successful =
true;
418 #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".
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
double getResolution() const
Accessor for the resolution of the costmap.
A costmap grid collision checker.
void setFootprint(const nav2_costmap_2d::Footprint &footprint, const bool &radius, const double &possible_inscribed_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) 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.