49 : costmap_(NULL), planner_(), initialized_(false), allow_unknown_(true) {}
52 : costmap_(NULL), planner_(), initialized_(false), allow_unknown_(true) {
58 : costmap_(NULL), planner_(), initialized_(false), allow_unknown_(true) {
63 void NavfnROS::initialize(std::string name,
costmap_2d::Costmap2D* costmap, std::string global_frame){
66 global_frame_ = global_frame;
71 plan_pub_ = private_nh.advertise<nav_msgs::Path>(
"plan", 1);
73 private_nh.param(
"visualize_potential", visualize_potential_,
false);
76 if(visualize_potential_)
77 potarr_pub_ = private_nh.advertise<sensor_msgs::PointCloud2>(
"potential", 1);
79 private_nh.param(
"allow_unknown", allow_unknown_,
true);
80 private_nh.param(
"planner_window_x", planner_window_x_, 0.0);
81 private_nh.param(
"planner_window_y", planner_window_y_, 0.0);
82 private_nh.param(
"default_tolerance", default_tolerance_, 0.0);
84 make_plan_srv_ = private_nh.advertiseService(
"make_plan", &NavfnROS::makePlanService,
this);
89 ROS_WARN(
"This planner has already been initialized, you can't call it twice, doing nothing");
96 bool NavfnROS::validPointPotential(
const geometry_msgs::Point& world_point){
97 return validPointPotential(world_point, default_tolerance_);
100 bool NavfnROS::validPointPotential(
const geometry_msgs::Point& world_point,
double tolerance){
102 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
106 double resolution = costmap_->getResolution();
107 geometry_msgs::Point p;
110 p.y = world_point.y - tolerance;
112 while(p.y <= world_point.y + tolerance){
113 p.x = world_point.x - tolerance;
114 while(p.x <= world_point.x + tolerance){
115 double potential = getPointPotential(p);
127 double NavfnROS::getPointPotential(
const geometry_msgs::Point& world_point){
129 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
134 if(!costmap_->worldToMap(world_point.x, world_point.y, mx, my))
137 unsigned int index = my * planner_->nx + mx;
138 return planner_->potarr[index];
141 bool NavfnROS::computePotential(
const geometry_msgs::Point& world_point){
143 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
148 planner_->setNavArr(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());
149 planner_->setCostmap(costmap_->getCharMap(),
true, allow_unknown_);
152 if(!costmap_->worldToMap(world_point.x, world_point.y, mx, my))
163 planner_->setStart(map_start);
164 planner_->setGoal(map_goal);
166 return planner_->calcNavFnDijkstra();
169 void NavfnROS::clearRobotCell(
const geometry_msgs::PoseStamped& global_pose,
unsigned int mx,
unsigned int my){
171 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
179 bool NavfnROS::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp){
180 makePlan(req.start, req.goal, resp.plan.poses);
183 resp.plan.header.frame_id = global_frame_;
188 void NavfnROS::mapToWorld(
double mx,
double my,
double& wx,
double& wy) {
189 wx = costmap_->getOriginX() + mx * costmap_->getResolution();
190 wy = costmap_->getOriginY() + my * costmap_->getResolution();
193 bool NavfnROS::makePlan(
const geometry_msgs::PoseStamped&
start,
194 const geometry_msgs::PoseStamped&
goal, std::vector<geometry_msgs::PoseStamped>& plan){
195 return makePlan(
start,
goal, default_tolerance_, plan);
198 bool NavfnROS::makePlan(
const geometry_msgs::PoseStamped&
start,
199 const geometry_msgs::PoseStamped&
goal,
double tolerance, std::vector<geometry_msgs::PoseStamped>& plan){
200 boost::mutex::scoped_lock lock(mutex_);
202 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
212 if(
goal.header.frame_id != global_frame_){
213 ROS_ERROR(
"The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.",
214 global_frame_.c_str(),
goal.header.frame_id.c_str());
218 if(
start.header.frame_id != global_frame_){
219 ROS_ERROR(
"The start pose passed to this planner must be in the %s frame. It is instead in the %s frame.",
220 global_frame_.c_str(),
start.header.frame_id.c_str());
224 double wx =
start.pose.position.x;
225 double wy =
start.pose.position.y;
228 if(!costmap_->worldToMap(wx, wy, mx, my)){
229 ROS_WARN_THROTTLE(1.0,
"The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
234 clearRobotCell(
start, mx, my);
237 planner_->setNavArr(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());
238 planner_->setCostmap(costmap_->getCharMap(),
true, allow_unknown_);
244 wx =
goal.pose.position.x;
245 wy =
goal.pose.position.y;
247 if(!costmap_->worldToMap(wx, wy, mx, my)){
248 if(tolerance <= 0.0){
249 ROS_WARN_THROTTLE(1.0,
"The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.");
260 planner_->setStart(map_goal);
261 planner_->setGoal(map_start);
264 planner_->calcNavFnDijkstra(
true);
266 double resolution = costmap_->getResolution();
267 geometry_msgs::PoseStamped p, best_pose;
270 bool found_legal =
false;
271 double best_sdist = DBL_MAX;
273 p.pose.position.y =
goal.pose.position.y - tolerance;
275 while(p.pose.position.y <=
goal.pose.position.y + tolerance){
276 p.pose.position.x =
goal.pose.position.x - tolerance;
277 while(p.pose.position.x <=
goal.pose.position.x + tolerance){
278 double potential = getPointPotential(p.pose.position);
279 double sdist = sq_distance(p,
goal);
280 if(potential <
POT_HIGH && sdist < best_sdist){
285 p.pose.position.x += resolution;
287 p.pose.position.y += resolution;
292 if(getPlanFromPotential(best_pose, plan)){
294 geometry_msgs::PoseStamped goal_copy = best_pose;
296 plan.push_back(goal_copy);
299 ROS_ERROR(
"Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
303 if (visualize_potential_)
306 sensor_msgs::PointCloud2 cloud;
310 cloud.header.frame_id = global_frame_;
312 cloud_mod.setPointCloud2Fields(4,
"x", 1, sensor_msgs::PointField::FLOAT32,
313 "y", 1, sensor_msgs::PointField::FLOAT32,
314 "z", 1, sensor_msgs::PointField::FLOAT32,
315 "pot", 1, sensor_msgs::PointField::FLOAT32);
316 cloud_mod.resize(planner_->ny * planner_->nx);
320 float *pp = planner_->potarr;
322 for (
unsigned int i = 0; i < (
unsigned int)planner_->ny*planner_->nx ; i++)
326 mapToWorld(i%planner_->nx, i/planner_->nx, pot_x, pot_y);
329 iter_x[2] = pp[i]/pp[planner_->start[1]*planner_->nx + planner_->start[0]]*20;
334 potarr_pub_.publish(cloud);
338 publishPlan(plan, 0.0, 1.0, 0.0, 0.0);
340 return !plan.empty();
343 void NavfnROS::publishPlan(
const std::vector<geometry_msgs::PoseStamped>& path,
double r,
double g,
double b,
double a){
345 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
350 nav_msgs::Path gui_path;
351 gui_path.poses.resize(path.size());
355 gui_path.header.frame_id = global_frame_;
358 gui_path.header.frame_id = path[0].header.frame_id;
359 gui_path.header.stamp = path[0].header.stamp;
363 for(
unsigned int i=0; i < path.size(); i++){
364 gui_path.poses[i] = path[i];
367 plan_pub_.publish(gui_path);
370 bool NavfnROS::getPlanFromPotential(
const geometry_msgs::PoseStamped&
goal, std::vector<geometry_msgs::PoseStamped>& plan){
372 ROS_ERROR(
"This planner has not been initialized yet, but it is being used, please call initialize() before use");
380 if(
goal.header.frame_id != global_frame_){
381 ROS_ERROR(
"The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.",
382 global_frame_.c_str(),
goal.header.frame_id.c_str());
386 double wx =
goal.pose.position.x;
387 double wy =
goal.pose.position.y;
391 if(!costmap_->worldToMap(wx, wy, mx, my)){
392 ROS_WARN_THROTTLE(1.0,
"The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.");
400 planner_->setStart(map_goal);
402 planner_->calcPath(costmap_->getSizeInCellsX() * 4);
405 float *x = planner_->getPathX();
406 float *y = planner_->getPathY();
407 int len = planner_->getPathLen();
410 for(
int i = len - 1; i >= 0; --i){
412 double world_x, world_y;
413 mapToWorld(x[i], y[i], world_x, world_y);
415 geometry_msgs::PoseStamped pose;
416 pose.header.stamp = plan_time;
417 pose.header.frame_id = global_frame_;
418 pose.pose.position.x = world_x;
419 pose.pose.position.y = world_y;
420 pose.pose.position.z = 0.0;
421 pose.pose.orientation.x = 0.0;
422 pose.pose.orientation.y = 0.0;
423 pose.pose.orientation.z = 0.0;
424 pose.pose.orientation.w = 1.0;
425 plan.push_back(pose);
429 publishPlan(plan, 0.0, 1.0, 0.0, 0.0);
430 return !plan.empty();