24 #include "nav2_navfn_planner/navfn_planner.hpp"
35 #include "builtin_interfaces/msg/duration.hpp"
36 #include "nav2_navfn_planner/navfn.hpp"
37 #include "nav2_util/costmap.hpp"
38 #include "nav2_util/node_utils.hpp"
39 #include "nav2_costmap_2d/cost_values.hpp"
41 using namespace std::chrono_literals;
42 using namespace std::chrono;
43 using nav2_util::declare_parameter_if_not_declared;
44 using rcl_interfaces::msg::ParameterType;
45 using std::placeholders::_1;
47 namespace nav2_navfn_planner
50 NavfnPlanner::NavfnPlanner()
51 : tf_(nullptr), costmap_(nullptr)
58 logger_,
"Destroying plugin %s of type NavfnPlanner",
64 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
65 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
66 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
70 costmap_ = costmap_ros->getCostmap();
71 global_frame_ = costmap_ros->getGlobalFrameID();
74 auto node = parent.lock();
75 clock_ = node->get_clock();
76 logger_ = node->get_logger();
79 logger_,
"Configuring plugin %s of type NavfnPlanner",
84 declare_parameter_if_not_declared(node, name +
".tolerance", rclcpp::ParameterValue(0.5));
85 node->get_parameter(name +
".tolerance", tolerance_);
86 declare_parameter_if_not_declared(node, name +
".use_astar", rclcpp::ParameterValue(
false));
87 node->get_parameter(name +
".use_astar", use_astar_);
88 declare_parameter_if_not_declared(node, name +
".allow_unknown", rclcpp::ParameterValue(
true));
89 node->get_parameter(name +
".allow_unknown", allow_unknown_);
90 declare_parameter_if_not_declared(
91 node, name +
".use_final_approach_orientation", rclcpp::ParameterValue(
false));
92 node->get_parameter(name +
".use_final_approach_orientation", use_final_approach_orientation_);
95 planner_ = std::make_unique<NavFn>(
104 logger_,
"Activating plugin %s of type NavfnPlanner",
107 auto node = node_.lock();
108 dyn_params_handler_ = node->add_on_set_parameters_callback(
116 logger_,
"Deactivating plugin %s of type NavfnPlanner",
118 auto node = node_.lock();
119 if (dyn_params_handler_ && node) {
120 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
122 dyn_params_handler_.reset();
129 logger_,
"Cleaning up plugin %s of type NavfnPlanner",
135 const geometry_msgs::msg::PoseStamped & start,
136 const geometry_msgs::msg::PoseStamped & goal,
137 std::function<
bool()> cancel_checker)
139 #ifdef BENCHMARK_TESTING
140 steady_clock::time_point a = steady_clock::now();
142 unsigned int mx_start, my_start, mx_goal, my_goal;
143 if (!costmap_->
worldToMap(start.pose.position.x, start.pose.position.y, mx_start, my_start)) {
145 "Start Coordinates of(" + std::to_string(start.pose.position.x) +
", " +
146 std::to_string(start.pose.position.y) +
") was outside bounds");
149 if (!costmap_->
worldToMap(goal.pose.position.x, goal.pose.position.y, mx_goal, my_goal)) {
151 "Goal Coordinates of(" + std::to_string(goal.pose.position.x) +
", " +
152 std::to_string(goal.pose.position.y) +
") was outside bounds");
155 if (tolerance_ == 0 && costmap_->
getCost(mx_goal, my_goal) == nav2_costmap_2d::LETHAL_OBSTACLE) {
157 "Goal Coordinates of(" + std::to_string(goal.pose.position.x) +
", " +
158 std::to_string(goal.pose.position.y) +
") was in lethal cost");
168 nav_msgs::msg::Path path;
171 if (start.pose.position.x == goal.pose.position.x &&
172 start.pose.position.y == goal.pose.position.y)
174 path.header.stamp = clock_->now();
175 path.header.frame_id = global_frame_;
176 geometry_msgs::msg::PoseStamped pose;
177 pose.header = path.header;
178 pose.pose.position.z = 0.0;
180 pose.pose = start.pose;
184 if (start.pose.orientation != goal.pose.orientation && !use_final_approach_orientation_) {
185 pose.pose.orientation = goal.pose.orientation;
187 path.poses.push_back(pose);
191 if (!
makePlan(start.pose, goal.pose, tolerance_, cancel_checker, path)) {
193 "Failed to create plan with tolerance of: " + std::to_string(tolerance_) );
197 #ifdef BENCHMARK_TESTING
198 steady_clock::time_point b = steady_clock::now();
199 duration<double> time_span = duration_cast<duration<double>>(b - a);
200 std::cout <<
"It took " << time_span.count() * 1000 << std::endl;
209 if (!planner_.get() ||
220 const geometry_msgs::msg::Pose & start,
221 const geometry_msgs::msg::Pose & goal,
double tolerance,
222 std::function<
bool()> cancel_checker,
223 nav_msgs::msg::Path & plan)
228 plan.header.stamp = clock_->now();
229 plan.header.frame_id = global_frame_;
231 double wx = start.position.x;
232 double wy = start.position.y;
235 logger_,
"Making plan from (%.2f,%.2f) to (%.2f,%.2f)",
236 start.position.x, start.position.y, goal.position.x, goal.position.y);
244 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
251 planner_->setCostmap(costmap_->
getCharMap(),
true, allow_unknown_);
259 wx = goal.position.x;
260 wy = goal.position.y;
267 planner_->setStart(map_goal);
268 planner_->setGoal(map_start);
270 planner_->calcNavFnAstar(cancel_checker);
272 planner_->calcNavFnDijkstra(cancel_checker,
true);
276 geometry_msgs::msg::Pose p, best_pose;
278 bool found_legal =
false;
282 if (potential < POT_HIGH) {
289 double best_sdist = std::numeric_limits<double>::max();
291 p.position.y = goal.position.y - tolerance;
292 while (p.position.y <= goal.position.y + tolerance) {
293 p.position.x = goal.position.x - tolerance;
294 while (p.position.x <= goal.position.x + tolerance) {
297 if (potential < POT_HIGH && sdist < best_sdist) {
302 p.position.x += resolution;
304 p.position.y += resolution;
317 if (use_final_approach_orientation_) {
318 size_t plan_size = plan.poses.size();
319 if (plan_size == 1) {
320 plan.poses.back().pose.orientation = start.orientation;
321 }
else if (plan_size > 1) {
322 double dx, dy, theta;
323 auto last_pose = plan.poses.back().pose.position;
324 auto approach_pose = plan.poses[plan_size - 2].pose.position;
326 if (std::abs(last_pose.x - approach_pose.x) < 0.0001 &&
327 std::abs(last_pose.y - approach_pose.y) < 0.0001 && plan_size > 2)
329 approach_pose = plan.poses[plan_size - 3].pose.position;
331 dx = last_pose.x - approach_pose.x;
332 dy = last_pose.y - approach_pose.y;
333 theta = atan2(dy, dx);
334 plan.poses.back().pose.orientation =
335 nav2_util::geometry_utils::orientationAroundZAxis(theta);
341 "Failed to create a plan from potential when a legal"
342 " potential was found. This shouldn't happen.");
346 return !plan.poses.empty();
351 const geometry_msgs::msg::Pose & goal,
352 nav_msgs::msg::Path & plan)
356 if (plan.poses.size() >= 2) {
357 auto second_to_last_pose = plan.poses.end()[-2];
358 auto last_pose = plan.poses.back();
363 plan.poses.back().pose = goal;
367 geometry_msgs::msg::PoseStamped goal_copy;
368 goal_copy.pose = goal;
369 goal_copy.header = plan.header;
370 plan.poses.push_back(goal_copy);
375 const geometry_msgs::msg::Pose & goal,
376 nav_msgs::msg::Path & plan)
382 double wx = goal.position.x;
383 double wy = goal.position.y;
393 planner_->setStart(map_goal);
398 int path_len = planner_->calcPath(max_cycles);
403 auto cost = planner_->getLastPathCost();
406 "Path found, %d steps, %f cost\n", path_len, cost);
409 float * x = planner_->getPathX();
410 float * y = planner_->getPathY();
411 int len = planner_->getPathLen();
413 for (
int i = len - 1; i >= 0; --i) {
415 double world_x, world_y;
418 geometry_msgs::msg::PoseStamped pose;
419 pose.header = plan.header;
420 pose.pose.position.x = world_x;
421 pose.pose.position.y = world_y;
422 pose.pose.position.z = 0.0;
423 pose.pose.orientation.x = 0.0;
424 pose.pose.orientation.y = 0.0;
425 pose.pose.orientation.z = 0.0;
426 pose.pose.orientation.w = 1.0;
427 plan.poses.push_back(pose);
430 return !plan.poses.empty();
437 if (!
worldToMap(world_point.x, world_point.y, mx, my)) {
438 return std::numeric_limits<double>::max();
441 unsigned int index = my * planner_->nx + mx;
442 return planner_->potarr[index];
485 if (wx < costmap_->getOriginX() || wy < costmap_->getOriginY()) {
489 mx =
static_cast<int>(
491 my =
static_cast<int>(
494 if (mx < costmap_->getSizeInCellsX() && my < costmap_->
getSizeInCellsY()) {
500 "worldToMap failed: mx,my: %d,%d, size_x,size_y: %d,%d", mx, my,
518 costmap_->
setCost(mx, my, nav2_costmap_2d::FREE_SPACE);
521 rcl_interfaces::msg::SetParametersResult
524 rcl_interfaces::msg::SetParametersResult result;
525 for (
auto parameter : parameters) {
526 const auto & type = parameter.get_type();
527 const auto & name = parameter.get_name();
529 if (type == ParameterType::PARAMETER_DOUBLE) {
530 if (name == name_ +
".tolerance") {
531 tolerance_ = parameter.as_double();
533 }
else if (type == ParameterType::PARAMETER_BOOL) {
534 if (name == name_ +
".use_astar") {
535 use_astar_ = parameter.as_bool();
536 }
else if (name == name_ +
".allow_unknown") {
537 allow_unknown_ = parameter.as_bool();
538 }
else if (name == name_ +
".use_final_approach_orientation") {
539 use_final_approach_orientation_ = parameter.as_bool();
543 result.successful =
true;
549 #include "pluginlib/class_list_macros.hpp"
Abstract interface for global planners to adhere to with pluginlib.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as 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.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
double getOriginY() const
Accessor for the y origin of the costmap.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
double getOriginX() const
Accessor for the x origin of the costmap.
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
double squared_distance(const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2)
Compute the squared distance between two points.
~NavfnPlanner()
destructor
double getPointPotential(const geometry_msgs::msg::Point &world_point)
Compute the potential, or navigation cost, at a given point in the world must call computePotential f...
void activate() override
Activate lifecycle node.
void mapToWorld(double mx, double my, double &wx, double &wy)
Transform a point from map to world frame.
bool makePlan(const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &goal, double tolerance, std::function< bool()> cancel_checker, nav_msgs::msg::Path &plan)
Compute a plan given start and goal poses, provided in global world frame.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my)
Transform a point from world to map frame.
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.
bool isPlannerOutOfDate()
Determine if a new planner object should be made.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
void clearRobotCell(unsigned int mx, unsigned int my)
Set the corresponding cell cost to be free space.
void smoothApproachToGoal(const geometry_msgs::msg::Pose &goal, nav_msgs::msg::Path &plan)
Remove artifacts at the end of the path - originated from planning on a discretized world.
void cleanup() override
Cleanup 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.
void deactivate() override
Deactivate lifecycle node.
bool getPlanFromPotential(const geometry_msgs::msg::Pose &goal, nav_msgs::msg::Path &plan)
Compute a plan to a goal from a potential - must call computePotential first.