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 dyn_params_handler_.reset();
125 logger_,
"Cleaning up plugin %s of type NavfnPlanner",
131 const geometry_msgs::msg::PoseStamped & start,
132 const geometry_msgs::msg::PoseStamped & goal)
134 #ifdef BENCHMARK_TESTING
135 steady_clock::time_point a = steady_clock::now();
145 nav_msgs::msg::Path path;
148 if (start.pose.position.x == goal.pose.position.x &&
149 start.pose.position.y == goal.pose.position.y)
152 costmap_->
worldToMap(start.pose.position.x, start.pose.position.y, mx, my);
153 if (costmap_->
getCost(mx, my) == nav2_costmap_2d::LETHAL_OBSTACLE) {
154 RCLCPP_WARN(logger_,
"Failed to create a unique pose path because of obstacles");
157 path.header.stamp = clock_->now();
158 path.header.frame_id = global_frame_;
159 geometry_msgs::msg::PoseStamped pose;
160 pose.header = path.header;
161 pose.pose.position.z = 0.0;
163 pose.pose = start.pose;
167 if (start.pose.orientation != goal.pose.orientation && !use_final_approach_orientation_) {
168 pose.pose.orientation = goal.pose.orientation;
170 path.poses.push_back(pose);
174 if (!
makePlan(start.pose, goal.pose, tolerance_, path)) {
176 logger_,
"%s: failed to create plan with "
177 "tolerance %.2f.", name_.c_str(), tolerance_);
181 #ifdef BENCHMARK_TESTING
182 steady_clock::time_point b = steady_clock::now();
183 duration<double> time_span = duration_cast<duration<double>>(b - a);
184 std::cout <<
"It took " << time_span.count() * 1000 << std::endl;
193 if (!planner_.get() ||
204 const geometry_msgs::msg::Pose & start,
205 const geometry_msgs::msg::Pose & goal,
double tolerance,
206 nav_msgs::msg::Path & plan)
211 plan.header.stamp = clock_->now();
212 plan.header.frame_id = global_frame_;
214 double wx = start.position.x;
215 double wy = start.position.y;
218 logger_,
"Making plan from (%.2f,%.2f) to (%.2f,%.2f)",
219 start.position.x, start.position.y, goal.position.x, goal.position.y);
225 "Cannot create a plan: the robot's start position is off the global"
226 " costmap. Planning will always fail, are you sure"
227 " the robot has been properly localized?");
234 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
241 planner_->setCostmap(costmap_->
getCharMap(),
true, allow_unknown_);
249 wx = goal.position.x;
250 wy = goal.position.y;
255 "The goal sent to the planner is off the global costmap."
256 " Planning will always fail to this goal.");
264 planner_->setStart(map_goal);
265 planner_->setGoal(map_start);
267 planner_->calcNavFnAstar();
269 planner_->calcNavFnDijkstra(
true);
273 geometry_msgs::msg::Pose p, best_pose;
275 bool found_legal =
false;
279 if (potential < POT_HIGH) {
286 double best_sdist = std::numeric_limits<double>::max();
288 p.position.y = goal.position.y - tolerance;
289 while (p.position.y <= goal.position.y + tolerance) {
290 p.position.x = goal.position.x - tolerance;
291 while (p.position.x <= goal.position.x + tolerance) {
294 if (potential < POT_HIGH && sdist < best_sdist) {
299 p.position.x += resolution;
301 p.position.y += resolution;
314 if (use_final_approach_orientation_) {
315 size_t plan_size = plan.poses.size();
316 if (plan_size == 1) {
317 plan.poses.back().pose.orientation = start.orientation;
318 }
else if (plan_size > 1) {
319 double dx, dy, theta;
320 auto last_pose = plan.poses.back().pose.position;
321 auto approach_pose = plan.poses[plan_size - 2].pose.position;
323 if (std::abs(last_pose.x - approach_pose.x) < 0.0001 &&
324 std::abs(last_pose.y - approach_pose.y) < 0.0001 && plan_size > 2)
326 approach_pose = plan.poses[plan_size - 3].pose.position;
328 dx = last_pose.x - approach_pose.x;
329 dy = last_pose.y - approach_pose.y;
330 theta = atan2(dy, dx);
331 plan.poses.back().pose.orientation =
332 nav2_util::geometry_utils::orientationAroundZAxis(theta);
338 "Failed to create a plan from potential when a legal"
339 " potential was found. This shouldn't happen.");
343 return !plan.poses.empty();
348 const geometry_msgs::msg::Pose & goal,
349 nav_msgs::msg::Path & plan)
353 if (plan.poses.size() >= 2) {
354 auto second_to_last_pose = plan.poses.end()[-2];
355 auto last_pose = plan.poses.back();
360 plan.poses.back().pose = goal;
364 geometry_msgs::msg::PoseStamped goal_copy;
365 goal_copy.pose = goal;
366 goal_copy.header = plan.header;
367 plan.poses.push_back(goal_copy);
372 const geometry_msgs::msg::Pose & goal,
373 nav_msgs::msg::Path & plan)
379 double wx = goal.position.x;
380 double wy = goal.position.y;
387 "The goal sent to the navfn planner is off the global costmap."
388 " Planning will always fail to this goal.");
396 planner_->setStart(map_goal);
401 int path_len = planner_->calcPath(max_cycles);
406 auto cost = planner_->getLastPathCost();
409 "Path found, %d steps, %f cost\n", path_len, cost);
412 float * x = planner_->getPathX();
413 float * y = planner_->getPathY();
414 int len = planner_->getPathLen();
416 for (
int i = len - 1; i >= 0; --i) {
418 double world_x, world_y;
421 geometry_msgs::msg::PoseStamped pose;
422 pose.header = plan.header;
423 pose.pose.position.x = world_x;
424 pose.pose.position.y = world_y;
425 pose.pose.position.z = 0.0;
426 pose.pose.orientation.x = 0.0;
427 pose.pose.orientation.y = 0.0;
428 pose.pose.orientation.z = 0.0;
429 pose.pose.orientation.w = 1.0;
430 plan.poses.push_back(pose);
433 return !plan.poses.empty();
440 if (!
worldToMap(world_point.x, world_point.y, mx, my)) {
441 return std::numeric_limits<double>::max();
444 unsigned int index = my * planner_->nx + mx;
445 return planner_->potarr[index];
488 if (wx < costmap_->getOriginX() || wy < costmap_->getOriginY()) {
492 mx =
static_cast<int>(
494 my =
static_cast<int>(
497 if (mx < costmap_->getSizeInCellsX() && my < costmap_->
getSizeInCellsY()) {
503 "worldToMap failed: mx,my: %d,%d, size_x,size_y: %d,%d", mx, my,
521 costmap_->
setCost(mx, my, nav2_costmap_2d::FREE_SPACE);
524 rcl_interfaces::msg::SetParametersResult
527 rcl_interfaces::msg::SetParametersResult result;
528 for (
auto parameter : parameters) {
529 const auto & type = parameter.get_type();
530 const auto & name = parameter.get_name();
532 if (type == ParameterType::PARAMETER_DOUBLE) {
533 if (name == name_ +
".tolerance") {
534 tolerance_ = parameter.as_double();
536 }
else if (type == ParameterType::PARAMETER_BOOL) {
537 if (name == name_ +
".use_astar") {
538 use_astar_ = parameter.as_bool();
539 }
else if (name == name_ +
".allow_unknown") {
540 allow_unknown_ = parameter.as_bool();
541 }
else if (name == name_ +
".use_final_approach_orientation") {
542 use_final_approach_orientation_ = parameter.as_bool();
546 result.successful =
true;
552 #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.
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.
double squared_distance(const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2)
Compute the squared distance between two points.
bool makePlan(const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &goal, double tolerance, nav_msgs::msg::Path &plan)
Compute a plan given start and goal poses, provided in global world frame.
~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 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.
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.