00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <navfn/navfn_ros.h>
00038 #include <pluginlib/class_list_macros.h>
00039
00040
00041 PLUGINLIB_EXPORT_CLASS( navfn::NavfnROS, nav_core::BaseGlobalPlanner)
00042
00043 namespace navfn {
00044
00045 NavfnROS::NavfnROS()
00046 : costmap_ros_(NULL), planner_(), initialized_(false), allow_unknown_(true), costmap_publisher_(NULL) {}
00047
00048 NavfnROS::NavfnROS(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
00049 : costmap_ros_(NULL), planner_(), initialized_(false), allow_unknown_(true) {
00050
00051 initialize(name, costmap_ros);
00052 }
00053
00054 void NavfnROS::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros){
00055 if(!initialized_){
00056 costmap_ros_ = costmap_ros;
00057 planner_ = boost::shared_ptr<NavFn>(new NavFn(costmap_ros->getSizeInCellsX(), costmap_ros->getSizeInCellsY()));
00058
00059
00060 costmap_ros_->getCostmapCopy(costmap_);
00061
00062 ros::NodeHandle private_nh("~/" + name);
00063
00064 plan_pub_ = private_nh.advertise<nav_msgs::Path>("plan", 1);
00065
00066 private_nh.param("visualize_potential", visualize_potential_, false);
00067
00068
00069 if(visualize_potential_)
00070 potarr_pub_.advertise(private_nh, "potential", 1);
00071
00072 private_nh.param("allow_unknown", allow_unknown_, true);
00073 private_nh.param("planner_window_x", planner_window_x_, 0.0);
00074 private_nh.param("planner_window_y", planner_window_y_, 0.0);
00075 private_nh.param("default_tolerance", default_tolerance_, 0.0);
00076
00077 double costmap_pub_freq;
00078 private_nh.param("planner_costmap_publish_frequency", costmap_pub_freq, 0.0);
00079
00080
00081 std::string global_frame = costmap_ros_->getGlobalFrameID();
00082
00083
00084 inscribed_radius_ = costmap_ros_->getInscribedRadius();
00085 circumscribed_radius_ = costmap_ros_->getCircumscribedRadius();
00086 inflation_radius_ = costmap_ros_->getInflationRadius();
00087
00088
00089 costmap_publisher_ = new costmap_2d::Costmap2DPublisher(ros::NodeHandle(private_nh, "NavfnROS_costmap"), costmap_pub_freq, global_frame);
00090
00091
00092 ros::NodeHandle prefix_nh;
00093 tf_prefix_ = tf::getPrefixParam(prefix_nh);
00094
00095 make_plan_srv_ = private_nh.advertiseService("make_plan", &NavfnROS::makePlanService, this);
00096
00097 initialized_ = true;
00098 }
00099 else
00100 ROS_WARN("This planner has already been initialized, you can't call it twice, doing nothing");
00101 }
00102
00103 bool NavfnROS::validPointPotential(const geometry_msgs::Point& world_point){
00104 return validPointPotential(world_point, default_tolerance_);
00105 }
00106
00107 bool NavfnROS::validPointPotential(const geometry_msgs::Point& world_point, double tolerance){
00108 if(!initialized_){
00109 ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00110 return false;
00111 }
00112
00113 double resolution = costmap_ros_->getResolution();
00114 geometry_msgs::Point p;
00115 p = world_point;
00116
00117 p.y = world_point.y - tolerance;
00118
00119 while(p.y <= world_point.y + tolerance){
00120 p.x = world_point.x - tolerance;
00121 while(p.x <= world_point.x + tolerance){
00122 double potential = getPointPotential(p);
00123 if(potential < POT_HIGH){
00124 return true;
00125 }
00126 p.x += resolution;
00127 }
00128 p.y += resolution;
00129 }
00130
00131 return false;
00132 }
00133
00134 double NavfnROS::getPointPotential(const geometry_msgs::Point& world_point){
00135 if(!initialized_){
00136 ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00137 return -1.0;
00138 }
00139
00140 unsigned int mx, my;
00141 if(!costmap_.worldToMap(world_point.x, world_point.y, mx, my))
00142 return DBL_MAX;
00143
00144 unsigned int index = my * planner_->nx + mx;
00145 return planner_->potarr[index];
00146 }
00147
00148 bool NavfnROS::computePotential(const geometry_msgs::Point& world_point){
00149 if(!initialized_){
00150 ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00151 return false;
00152 }
00153
00154
00155 getCostmap(costmap_);
00156
00157
00158 planner_->setNavArr(costmap_.getSizeInCellsX(), costmap_.getSizeInCellsY());
00159 planner_->setCostmap(costmap_.getCharMap(), true, allow_unknown_);
00160
00161 unsigned int mx, my;
00162 if(!costmap_.worldToMap(world_point.x, world_point.y, mx, my))
00163 return false;
00164
00165 int map_start[2];
00166 map_start[0] = 0;
00167 map_start[1] = 0;
00168
00169 int map_goal[2];
00170 map_goal[0] = mx;
00171 map_goal[1] = my;
00172
00173 planner_->setStart(map_start);
00174 planner_->setGoal(map_goal);
00175
00176 return planner_->calcNavFnDijkstra();
00177 }
00178
00179 void NavfnROS::clearRobotCell(const tf::Stamped<tf::Pose>& global_pose, unsigned int mx, unsigned int my){
00180 if(!initialized_){
00181 ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00182 return;
00183 }
00184
00185
00186 costmap_.setCost(mx, my, costmap_2d::FREE_SPACE);
00187
00188 double max_inflation_dist = inflation_radius_ + inscribed_radius_;
00189
00190
00191 costmap_.reinflateWindow(global_pose.getOrigin().x(), global_pose.getOrigin().y(), max_inflation_dist, max_inflation_dist);
00192
00193
00194 costmap_.setCost(mx, my, costmap_2d::FREE_SPACE);
00195
00196 }
00197
00198 void NavfnROS::getCostmap(costmap_2d::Costmap2D& costmap)
00199 {
00200 if(!initialized_){
00201 ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00202 return;
00203 }
00204
00205 costmap_ros_->clearRobotFootprint();
00206
00207
00208 if(planner_window_x_ > 1e-6 && planner_window_y_ > 1e-6){
00209 costmap_ros_->getCostmapWindowCopy(planner_window_x_, planner_window_y_, costmap_);
00210 }
00211 else{
00212 costmap_ros_->getCostmapCopy(costmap);
00213 }
00214
00215
00216 if(costmap_publisher_->active()){
00217 std::vector<geometry_msgs::Point> oriented_footprint;
00218 costmap_ros_->getOrientedFootprint(oriented_footprint);
00219 tf::Stamped<tf::Pose> global_pose;
00220 costmap_ros_->getRobotPose(global_pose);
00221 costmap_publisher_->updateCostmapData(costmap, oriented_footprint, global_pose);
00222 }
00223
00224 }
00225
00226 bool NavfnROS::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp){
00227 makePlan(req.start, req.goal, resp.plan.poses);
00228
00229 resp.plan.header.stamp = ros::Time::now();
00230 resp.plan.header.frame_id = costmap_ros_->getGlobalFrameID();
00231
00232 return true;
00233 }
00234
00235 void NavfnROS::mapToWorld(double mx, double my, double& wx, double& wy) {
00236 wx = costmap_.getOriginX() + mx * costmap_.getResolution();
00237 wy = costmap_.getOriginY() + my * costmap_.getResolution();
00238 }
00239
00240 bool NavfnROS::makePlan(const geometry_msgs::PoseStamped& start,
00241 const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
00242 return makePlan(start, goal, default_tolerance_, plan);
00243 }
00244
00245 bool NavfnROS::makePlan(const geometry_msgs::PoseStamped& start,
00246 const geometry_msgs::PoseStamped& goal, double tolerance, std::vector<geometry_msgs::PoseStamped>& plan){
00247 boost::mutex::scoped_lock lock(mutex_);
00248 if(!initialized_){
00249 ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00250 return false;
00251 }
00252
00253
00254 plan.clear();
00255
00256
00257 getCostmap(costmap_);
00258
00259
00260 #if 0
00261 {
00262 static int n = 0;
00263 static char filename[1000];
00264 snprintf( filename, 1000, "navfnros-makeplan-costmapA-%04d.pgm", n++ );
00265 costmap_.saveRawMap( std::string( filename ));
00266 }
00267 #endif
00268
00269 ros::NodeHandle n;
00270
00271
00272 if(tf::resolve(tf_prefix_, goal.header.frame_id) != tf::resolve(tf_prefix_, costmap_ros_->getGlobalFrameID())){
00273 ROS_ERROR("The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.",
00274 tf::resolve(tf_prefix_, costmap_ros_->getGlobalFrameID()).c_str(), tf::resolve(tf_prefix_, goal.header.frame_id).c_str());
00275 return false;
00276 }
00277
00278 if(tf::resolve(tf_prefix_, start.header.frame_id) != tf::resolve(tf_prefix_, costmap_ros_->getGlobalFrameID())){
00279 ROS_ERROR("The start pose passed to this planner must be in the %s frame. It is instead in the %s frame.",
00280 tf::resolve(tf_prefix_, costmap_ros_->getGlobalFrameID()).c_str(), tf::resolve(tf_prefix_, start.header.frame_id).c_str());
00281 return false;
00282 }
00283
00284 double wx = start.pose.position.x;
00285 double wy = start.pose.position.y;
00286
00287 unsigned int mx, my;
00288 if(!costmap_.worldToMap(wx, wy, mx, my)){
00289 ROS_WARN("The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
00290 return false;
00291 }
00292
00293
00294 tf::Stamped<tf::Pose> start_pose;
00295 tf::poseStampedMsgToTF(start, start_pose);
00296 clearRobotCell(start_pose, mx, my);
00297
00298 #if 0
00299 {
00300 static int n = 0;
00301 static char filename[1000];
00302 snprintf( filename, 1000, "navfnros-makeplan-costmapB-%04d.pgm", n++ );
00303 costmap_.saveRawMap( std::string( filename ));
00304 }
00305 #endif
00306
00307
00308 planner_->setNavArr(costmap_.getSizeInCellsX(), costmap_.getSizeInCellsY());
00309 planner_->setCostmap(costmap_.getCharMap(), true, allow_unknown_);
00310
00311 #if 0
00312 {
00313 static int n = 0;
00314 static char filename[1000];
00315 snprintf( filename, 1000, "navfnros-makeplan-costmapC-%04d", n++ );
00316 planner_->savemap( filename );
00317 }
00318 #endif
00319
00320 int map_start[2];
00321 map_start[0] = mx;
00322 map_start[1] = my;
00323
00324 wx = goal.pose.position.x;
00325 wy = goal.pose.position.y;
00326
00327 if(!costmap_.worldToMap(wx, wy, mx, my)){
00328 if(tolerance <= 0.0){
00329 ROS_WARN("The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.");
00330 return false;
00331 }
00332 mx = 0;
00333 my = 0;
00334 }
00335
00336 int map_goal[2];
00337 map_goal[0] = mx;
00338 map_goal[1] = my;
00339
00340 planner_->setStart(map_goal);
00341 planner_->setGoal(map_start);
00342
00343
00344 planner_->calcNavFnDijkstra(true);
00345
00346 double resolution = costmap_ros_->getResolution();
00347 geometry_msgs::PoseStamped p, best_pose;
00348 p = goal;
00349
00350 bool found_legal = false;
00351 double best_sdist = DBL_MAX;
00352
00353 p.pose.position.y = goal.pose.position.y - tolerance;
00354
00355 while(p.pose.position.y <= goal.pose.position.y + tolerance){
00356 p.pose.position.x = goal.pose.position.x - tolerance;
00357 while(p.pose.position.x <= goal.pose.position.x + tolerance){
00358 double potential = getPointPotential(p.pose.position);
00359 double sdist = sq_distance(p, goal);
00360 if(potential < POT_HIGH && sdist < best_sdist){
00361 best_sdist = sdist;
00362 best_pose = p;
00363 found_legal = true;
00364 }
00365 p.pose.position.x += resolution;
00366 }
00367 p.pose.position.y += resolution;
00368 }
00369
00370 if(found_legal){
00371
00372 if(getPlanFromPotential(best_pose, plan)){
00373
00374 geometry_msgs::PoseStamped goal_copy = best_pose;
00375 goal_copy.header.stamp = ros::Time::now();
00376 plan.push_back(goal_copy);
00377 }
00378 else{
00379 ROS_ERROR("Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
00380 }
00381 }
00382
00383 if (visualize_potential_){
00384
00385 pcl::PointCloud<PotarrPoint> pot_area;
00386 pot_area.header.frame_id = costmap_ros_->getGlobalFrameID();
00387 pot_area.points.clear();
00388 pot_area.header.stamp = ros::Time::now();
00389
00390 PotarrPoint pt;
00391 float *pp = planner_->potarr;
00392 double pot_x, pot_y;
00393 for (unsigned int i = 0; i < (unsigned int)planner_->ny*planner_->nx ; i++)
00394 {
00395 if (pp[i] < 10e7)
00396 {
00397 mapToWorld(i%planner_->nx, i/planner_->nx, pot_x, pot_y);
00398 pt.x = pot_x;
00399 pt.y = pot_y;
00400 pt.z = pp[i]/pp[planner_->start[1]*planner_->nx + planner_->start[0]]*20;
00401 pt.pot_value = pp[i];
00402 pot_area.push_back(pt);
00403 }
00404 }
00405 potarr_pub_.publish(pot_area);
00406 }
00407
00408
00409 publishPlan(plan, 0.0, 1.0, 0.0, 0.0);
00410
00411 return !plan.empty();
00412 }
00413
00414 void NavfnROS::publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, double r, double g, double b, double a){
00415 if(!initialized_){
00416 ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00417 return;
00418 }
00419
00420
00421 nav_msgs::Path gui_path;
00422 gui_path.poses.resize(path.size());
00423
00424 if(!path.empty())
00425 {
00426 gui_path.header.frame_id = path[0].header.frame_id;
00427 gui_path.header.stamp = path[0].header.stamp;
00428 }
00429
00430
00431 for(unsigned int i=0; i < path.size(); i++){
00432 gui_path.poses[i] = path[i];
00433 }
00434
00435 plan_pub_.publish(gui_path);
00436 }
00437
00438 bool NavfnROS::getPlanFromPotential(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
00439 if(!initialized_){
00440 ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
00441 return false;
00442 }
00443
00444
00445 plan.clear();
00446
00447
00448 if(tf::resolve(tf_prefix_, goal.header.frame_id) != tf::resolve(tf_prefix_, costmap_ros_->getGlobalFrameID())){
00449 ROS_ERROR("The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.",
00450 tf::resolve(tf_prefix_, costmap_ros_->getGlobalFrameID()).c_str(), tf::resolve(tf_prefix_, goal.header.frame_id).c_str());
00451 return false;
00452 }
00453
00454 double wx = goal.pose.position.x;
00455 double wy = goal.pose.position.y;
00456
00457
00458 unsigned int mx, my;
00459 if(!costmap_.worldToMap(wx, wy, mx, my)){
00460 ROS_WARN("The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal.");
00461 return false;
00462 }
00463
00464 int map_goal[2];
00465 map_goal[0] = mx;
00466 map_goal[1] = my;
00467
00468 planner_->setStart(map_goal);
00469
00470 planner_->calcPath(costmap_ros_->getSizeInCellsX() * 4);
00471
00472
00473 float *x = planner_->getPathX();
00474 float *y = planner_->getPathY();
00475 int len = planner_->getPathLen();
00476 ros::Time plan_time = ros::Time::now();
00477 std::string global_frame = costmap_ros_->getGlobalFrameID();
00478 for(int i = len - 1; i >= 0; --i){
00479
00480 double world_x, world_y;
00481 mapToWorld(x[i], y[i], world_x, world_y);
00482
00483 geometry_msgs::PoseStamped pose;
00484 pose.header.stamp = plan_time;
00485 pose.header.frame_id = global_frame;
00486 pose.pose.position.x = world_x;
00487 pose.pose.position.y = world_y;
00488 pose.pose.position.z = 0.0;
00489 pose.pose.orientation.x = 0.0;
00490 pose.pose.orientation.y = 0.0;
00491 pose.pose.orientation.z = 0.0;
00492 pose.pose.orientation.w = 1.0;
00493 plan.push_back(pose);
00494 }
00495
00496
00497 publishPlan(plan, 0.0, 1.0, 0.0, 0.0);
00498 return !plan.empty();
00499 }
00500 };