hector_exploration_planner.cpp
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2012, Mark Sollweck, Stefan Kohlbrecher, Florian Berz TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Simulation, Systems Optimization and Robotics
00013 //       group, TU Darmstadt nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #include <hector_exploration_planner/hector_exploration_planner.h>
00030 
00031 #include <visualization_msgs/Marker.h>
00032 #include <visualization_msgs/MarkerArray.h>
00033 #include <hector_nav_msgs/GetRobotTrajectory.h>
00034 #include <Eigen/Geometry>
00035 
00036 #include <hector_exploration_planner/ExplorationPlannerConfig.h>
00037 
00038 #define STRAIGHT_COST 100
00039 #define DIAGONAL_COST 141
00040 
00041 //#define STRAIGHT_COST 3
00042 //#define DIAGONAL_COST 4
00043 
00044 using namespace hector_exploration_planner;
00045 
00046 HectorExplorationPlanner::HectorExplorationPlanner()
00047 : costmap_ros_(0)
00048 , costmap_(0)
00049 , initialized_(false)
00050 , map_width_(0)
00051 , map_height_(0)
00052 , num_map_cells_(0)
00053 {}
00054 
00055 HectorExplorationPlanner::~HectorExplorationPlanner(){
00056   this->deleteMapData();
00057 }
00058 
00059 HectorExplorationPlanner::HectorExplorationPlanner(std::string name, costmap_2d::Costmap2DROS *costmap_ros_in) :
00060 costmap_ros_(NULL), initialized_(false) {
00061   HectorExplorationPlanner::initialize(name, costmap_ros_in);
00062 }
00063 
00064 void HectorExplorationPlanner::initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros_in){
00065 
00066   last_mode_ = FRONTIER_EXPLORE;
00067   // unknown: 255, obstacle 254, inflated: 253, free: 0
00068 
00069   if(initialized_){
00070     ROS_ERROR("[hector_exploration_planner] HectorExplorationPlanner is already initialized_! Please check why initialize() got called twice.");
00071     return;
00072   }
00073 
00074   ROS_INFO("[hector_exploration_planner] Initializing HectorExplorationPlanner");
00075 
00076   // initialize costmaps
00077   this->costmap_ros_ = costmap_ros_in;
00078   this->setupMapData();
00079 
00080   // initialize parameters
00081   ros::NodeHandle private_nh_("~/" + name);
00082   ros::NodeHandle nh;
00083   visualization_pub_ = private_nh_.advertise<visualization_msgs::Marker>("visualization_marker", 1);
00084 
00085   observation_pose_pub_ = private_nh_.advertise<geometry_msgs::PoseStamped>("observation_pose", 1, true);
00086   goal_pose_pub_ = private_nh_.advertise<geometry_msgs::PoseStamped>("goal_pose", 1, true);
00087 
00088   dyn_rec_server_.reset(new dynamic_reconfigure::Server<hector_exploration_planner::ExplorationPlannerConfig>(ros::NodeHandle("~/hector_exploration_planner")));
00089 
00090   dyn_rec_server_->setCallback(boost::bind(&HectorExplorationPlanner::dynRecParamCallback, this, _1, _2));
00091 
00092   path_service_client_ = nh.serviceClient<hector_nav_msgs::GetRobotTrajectory>("trajectory");
00093 
00094   ROS_INFO("[hector_exploration_planner] Parameter set. security_const: %f, min_obstacle_dist: %d, plan_in_unknown: %d, use_inflated_obstacle: %d, p_goal_angle_penalty_:%d , min_frontier_size: %d, p_dist_for_goal_reached_: %f, same_frontier: %f", p_alpha_, p_min_obstacle_dist_, p_plan_in_unknown_, p_use_inflated_obs_, p_goal_angle_penalty_, p_min_frontier_size_,p_dist_for_goal_reached_,p_same_frontier_dist_);
00095   //p_min_obstacle_dist_ = p_min_obstacle_dist_ * STRAIGHT_COST;
00096 
00097   this->name = name;
00098   this->initialized_ = true;
00099   this->previous_goal_ = -1;
00100 
00101   vis_.reset(new ExplorationTransformVis("exploration_transform"));
00102   close_path_vis_.reset(new ExplorationTransformVis("close_path_exploration_transform"));
00103   inner_vis_.reset(new ExplorationTransformVis("inner_exploration_transform"));
00104   obstacle_vis_.reset(new ExplorationTransformVis("obstacle_transform"));
00105 }
00106 
00107 void HectorExplorationPlanner::dynRecParamCallback(hector_exploration_planner::ExplorationPlannerConfig &config, uint32_t level)
00108 {
00109   p_plan_in_unknown_ = config.plan_in_unknown;
00110   p_explore_close_to_path_ = config.explore_close_to_path;
00111   p_use_inflated_obs_ = config.use_inflated_obstacles;
00112   p_goal_angle_penalty_ = config.goal_angle_penalty;
00113   p_alpha_ = config.security_constant;
00114   p_dist_for_goal_reached_ = config.dist_for_goal_reached;
00115   p_same_frontier_dist_ = config.same_frontier_distance;
00116   p_min_frontier_size_ = config.min_frontier_size;
00117   p_min_obstacle_dist_ = config.min_obstacle_dist * STRAIGHT_COST;
00118   p_obstacle_cutoff_dist_ = config.obstacle_cutoff_distance;
00119 
00120   p_use_observation_pose_calculation_ = config.use_observation_pose_calculation;
00121   p_observation_pose_desired_dist_ = config.observation_pose_desired_dist;
00122   double angle_rad = config.observation_pose_allowed_angle * (M_PI / 180.0);
00123   p_cos_of_allowed_observation_pose_angle_ = cos(angle_rad);
00124   p_close_to_path_target_distance_ = config.close_to_path_target_distance;
00125 }
00126 
00127 bool HectorExplorationPlanner::makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &original_goal, std::vector<geometry_msgs::PoseStamped> &plan){
00128 
00129   this->setupMapData();
00130 
00131   // do exploration? (not used anymore? -> call doExploration())
00132 
00133   if ((original_goal.pose.orientation.w == 0.0) && (original_goal.pose.orientation.x == 0.0) &&
00134   (original_goal.pose.orientation.y == 0.0) && (original_goal.pose.orientation.z == 0.0)){
00135       ROS_ERROR("Trying to plan with invalid quaternion, this shouldn't be done anymore, but we'll start exploration for now.");
00136       return doExploration(start,plan);
00137   }
00138 
00139 
00140   // planning
00141   ROS_INFO("[hector_exploration_planner] planning: starting to make a plan to given goal point");
00142 
00143   // setup maps and goals
00144   resetMaps();
00145   plan.clear();
00146 
00147   std::vector<geometry_msgs::PoseStamped> goals;
00148 
00149   // create obstacle tranform
00150   //buildobstacle_trans_array_(p_use_inflated_obs_);
00151 
00152   goal_pose_pub_.publish(original_goal);
00153 
00154   geometry_msgs::PoseStamped adjusted_goal;
00155 
00156   if (p_use_observation_pose_calculation_){
00157     ROS_INFO("Using observation pose calc.");
00158     if (!this->getObservationPose(original_goal, p_observation_pose_desired_dist_, adjusted_goal)){
00159       ROS_ERROR("getObservationPose returned false, no area around target point available to drive to!");
00160       return false;
00161     }
00162   }else{
00163     ROS_INFO("Not using observation pose calc.");
00164     this->buildobstacle_trans_array_(true);
00165     adjusted_goal = original_goal;
00166   }
00167 
00168   observation_pose_pub_.publish(adjusted_goal);
00169 
00170   // plan to given goal
00171   goals.push_back(adjusted_goal);
00172 
00173   // make plan
00174   if(!buildexploration_trans_array_(start,goals,true)){
00175     return false;
00176   }
00177   if(!getTrajectory(start,goals,plan)){
00178     return false;
00179   }
00180 
00181   // save and add last point
00182   plan.push_back(adjusted_goal);
00183   unsigned int mx,my;
00184   costmap_->worldToMap(adjusted_goal.pose.position.x,adjusted_goal.pose.position.y,mx,my);
00185   previous_goal_ = costmap_->getIndex(mx,my);
00186 
00187   if ((original_goal.pose.orientation.w == 0.0) && (original_goal.pose.orientation.x == 0.0) &&
00188   (original_goal.pose.orientation.y == 0.0) && (original_goal.pose.orientation.z == 0.0)){
00189       geometry_msgs::PoseStamped second_last_pose;
00190       geometry_msgs::PoseStamped last_pose;
00191       second_last_pose = plan[plan.size()-2];
00192       last_pose = plan[plan.size()-1];
00193       last_pose.pose.orientation = second_last_pose.pose.orientation;
00194       plan[plan.size()-1] = last_pose;
00195 
00196       
00197   }
00198 
00199   ROS_INFO("[hector_exploration_planner] planning: plan has been found! plansize: %u ", (unsigned int)plan.size());
00200   return true;
00201 }
00202 
00203 bool HectorExplorationPlanner::doExploration(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &plan){
00204 
00205 
00206 
00207   this->setupMapData();
00208 
00209   // setup maps and goals
00210 
00211   resetMaps();
00212   clearFrontiers();
00213   plan.clear();
00214 
00215   std::vector<geometry_msgs::PoseStamped> goals;
00216 
00217   // create obstacle tranform
00218   buildobstacle_trans_array_(p_use_inflated_obs_);
00219 
00220 
00221   bool frontiers_found = false;
00222 
00223   if (p_explore_close_to_path_){
00224 
00225     frontiers_found = findFrontiersCloseToPath(goals);
00226 
00227     if (!frontiers_found){
00228       ROS_WARN("Close Exploration desired, but no frontiers found. Falling back to normal exploration!");
00229       frontiers_found = findFrontiers(goals);
00230     }
00231 
00232   }else{
00233     frontiers_found = findFrontiers(goals);
00234   }
00235 
00236   // search for frontiers
00237   if(frontiers_found){
00238 
00239     last_mode_ = FRONTIER_EXPLORE;
00240     ROS_INFO("[hector_exploration_planner] exploration: found %u frontiers!", (unsigned int)goals.size());
00241   } else {
00242     ROS_INFO("[hector_exploration_planner] exploration: no frontiers have been found! starting inner-exploration");
00243     return doInnerExploration(start,plan);
00244   }
00245 
00246   // make plan
00247   if(!buildexploration_trans_array_(start,goals,true)){
00248     return false;
00249   }
00250 
00251   if(!getTrajectory(start,goals,plan)){
00252     ROS_INFO("[hector_exploration_planner] exploration: could not plan to frontier, starting inner-exploration");
00253     return doInnerExploration(start,plan);
00254   }
00255 
00256   // update previous goal
00257   if(!plan.empty()){
00258     geometry_msgs::PoseStamped thisgoal = plan.back();
00259     unsigned int mx,my;
00260     costmap_->worldToMap(thisgoal.pose.position.x,thisgoal.pose.position.y,mx,my);
00261     previous_goal_ = costmap_->getIndex(mx,my);
00262   }
00263 
00264 
00265   ROS_INFO("[hector_exploration_planner] exploration: plan to a frontier has been found! plansize: %u", (unsigned int)plan.size());
00266   return true;
00267 }
00268 
00269 bool HectorExplorationPlanner::doInnerExploration(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &plan){
00270   ROS_INFO("[hector_exploration_planner] inner-exploration: starting exploration");
00271 
00272   // setup maps and goals
00273 
00274   resetMaps();
00275   clearFrontiers();
00276   plan.clear();
00277 
00278   std::vector<geometry_msgs::PoseStamped> goals;
00279 
00280   // create obstacle tranform
00281   buildobstacle_trans_array_(p_use_inflated_obs_);
00282 
00283   // If we have been in inner explore before, check if we have reached the previous inner explore goal
00284   if (last_mode_ == INNER_EXPLORE){
00285 
00286     tf::Stamped<tf::Pose> robotPose;
00287     if(!costmap_ros_->getRobotPose(robotPose)){
00288       ROS_WARN("[hector_exploration_planner]: Failed to get RobotPose");
00289     }
00290 
00291     unsigned int xm, ym;
00292     costmap_->indexToCells(previous_goal_, xm, ym);
00293 
00294     double xw, yw;
00295     costmap_->mapToWorld(xm, ym, xw, yw);
00296 
00297     double dx = xw - robotPose.getOrigin().getX();
00298     double dy = yw - robotPose.getOrigin().getY();
00299 
00300     //If we have not  reached the previous goal, try planning and moving toward it.
00301     //If planning fails, we just continue below this block and try to find another inner frontier
00302     if ( (dx*dx + dy*dy) > 0.5*0.5){
00303 
00304       geometry_msgs::PoseStamped robotPoseMsg;
00305       tf::poseStampedTFToMsg(robotPose, robotPoseMsg);
00306 
00307       geometry_msgs::PoseStamped goalMsg;
00308       goalMsg.pose.position.x = xw;
00309       goalMsg.pose.position.y = yw;
00310       goalMsg.pose.orientation.w = 1.0;
00311 
00312       if(makePlan(robotPoseMsg, goalMsg, plan)){
00313         //Successfully generated plan to (previous) inner explore goal
00314         ROS_INFO("[hector_exploration_planner] inner-exploration: Planning to previous inner frontier");
00315         last_mode_ = INNER_EXPLORE;
00316         return true;
00317       }
00318     }
00319   }
00320 
00321   // search for frontiers
00322   if(findInnerFrontier(goals)){
00323     ROS_INFO("[hector_exploration_planner] inner-exploration: found %u inner-frontiers!", (unsigned int)goals.size());
00324   } else {
00325     ROS_WARN("[hector_exploration_planner] inner-exploration: no inner-frontiers have been found! exploration failed!");
00326     return false;
00327   }
00328 
00329   // make plan
00330   if(!buildexploration_trans_array_(start,goals,false)){
00331     ROS_WARN("[hector_exploration_planner] inner-exploration: Creating exploration transform failed!");
00332     return false;
00333   }
00334   if(!getTrajectory(start,goals,plan)){
00335     ROS_WARN("[hector_exploration_planner] inner-exploration: could not plan to inner-frontier. exploration failed!");
00336     return false;
00337   }
00338 
00339   // cutoff last points of plan due to sbpl error when planning close to walls
00340 
00341   int plansize = plan.size() - 5;
00342   if(plansize > 0 ){
00343     plan.resize(plansize);
00344   }
00345 
00346   // update previous goal
00347   if(!plan.empty()){
00348     const geometry_msgs::PoseStamped& thisgoal = plan.back();
00349     unsigned int mx,my;
00350     costmap_->worldToMap(thisgoal.pose.position.x,thisgoal.pose.position.y,mx,my);
00351     previous_goal_ = costmap_->getIndex(mx,my);
00352     last_mode_ = INNER_EXPLORE;
00353   }
00354 
00355   ROS_INFO("[hector_exploration_planner] inner-exploration: plan to an inner-frontier has been found! plansize: %u", (unsigned int)plan.size());
00356   return true;
00357 }
00358 
00359 bool HectorExplorationPlanner::getObservationPose(const geometry_msgs::PoseStamped& observation_pose, const double desired_distance, geometry_msgs::PoseStamped& new_observation_pose)
00360 {
00361   // We call this from inside the planner, so map data setup and reset already happened
00362   //this->setupMapData();
00363   //resetMaps();
00364 
00365   if (!p_use_observation_pose_calculation_){
00366     ROS_WARN("getObservationPose was called although use_observation_pose_calculation param is set to false. Returning original pose!");
00367     new_observation_pose = observation_pose;
00368     this->buildobstacle_trans_array_(true);
00369     return true;
00370   }
00371 
00372   unsigned int mxs,mys;
00373   costmap_->worldToMap(observation_pose.pose.position.x, observation_pose.pose.position.y, mxs, mys);
00374 
00375   double pose_yaw = tf::getYaw(observation_pose.pose.orientation);
00376 
00377   Eigen::Vector2f obs_pose_dir_vec (cos(pose_yaw), sin(pose_yaw));
00378 
00379   this->buildobstacle_trans_array_(true);
00380 
00381   int searchSize = 2.0 / costmap_->getResolution();
00382 
00383   int min_x = mxs - searchSize/2;
00384   int min_y = mys - searchSize/2;
00385 
00386   if (min_x < 0){
00387     min_x = 0;
00388   }
00389 
00390   if (min_y < 0){
00391     min_y = 0;
00392   }
00393 
00394   int max_x = mxs + searchSize/2;
00395   int max_y = mys + searchSize/2;
00396 
00397   if (max_x > static_cast<int>(costmap_->getSizeInCellsX())){
00398     max_x = static_cast<int>(costmap_->getSizeInCellsX()-1);
00399   }
00400 
00401   if (max_y > static_cast<int>(costmap_->getSizeInCellsY())){
00402     max_y = static_cast<int>(costmap_->getSizeInCellsY()-1);
00403   }
00404 
00405   int closest_x = -1;
00406   int closest_y = -1;
00407 
00408   unsigned int closest_sqr_dist = UINT_MAX;
00409 
00410   bool no_information = true;
00411 
00412   for (int x = min_x; x < max_x; ++x){
00413     for (int y = min_y; y < max_y; ++y){
00414 
00415       unsigned int point = costmap_->getIndex(x,y);
00416 
00417       unsigned int obstacle_trans_val = obstacle_trans_array_[point];
00418 
00419       if ( (obstacle_trans_val != UINT_MAX) && (obstacle_trans_val != 0) && (occupancy_grid_array_[point] != costmap_2d::NO_INFORMATION)){
00420 
00421         no_information = false;
00422 
00423         int diff_x = x - (int)mxs;
00424         int diff_y = y - (int)mys;
00425 
00426         unsigned int sqr_dist = diff_x*diff_x + diff_y*diff_y;
00427 
00428         //std::cout << "diff: " << diff_x << " , " << diff_y << " sqr_dist: " << sqr_dist << " pos: " << x << " , " << y << " closest sqr dist: " << closest_sqr_dist << " obstrans " << obstacle_trans_array_[costmap_->getIndex(x,y)] << "\n";
00429 
00430         if (sqr_dist < closest_sqr_dist){
00431 
00432           Eigen::Vector2f curr_dir_vec(static_cast<float>(diff_x), static_cast<float>(diff_y));
00433           curr_dir_vec.normalize();
00434 
00435           if (curr_dir_vec.dot(obs_pose_dir_vec) <  p_cos_of_allowed_observation_pose_angle_){
00436 
00437             closest_x = (unsigned int)x;
00438             closest_y = (unsigned int)y;
00439             closest_sqr_dist = sqr_dist;
00440           }
00441         }
00442       }
00443     }
00444   }
00445 
00446   if (no_information){
00447     new_observation_pose.pose = observation_pose.pose;
00448     new_observation_pose.pose.position.z = 0.0;
00449     ROS_INFO("Observation pose unchanged as no information available around goal area");
00450     return true;
00451   }
00452 
00453   //std::cout << "start: " << mxs << " , " << mys << " min: " << min_x << " , " << min_y << " max: " <<  max_x << " , " << max_y << "\n";
00454   //std::cout << "pos: " << closest_x << " , " << closest_y << "\n";
00455 
00456   // Found valid pose if both coords are larger than -1
00457   if ((closest_x > -1) && (closest_y > -1)){
00458 
00459     Eigen::Vector2d closest_point_world;
00460     costmap_->mapToWorld(closest_x, closest_y, closest_point_world.x(),  closest_point_world.y());
00461 
00462     Eigen::Vector2d original_goal_pose(observation_pose.pose.position.x, observation_pose.pose.position.y);
00463 
00464     //geometry_msgs::PoseStamped pose;
00465     new_observation_pose.header.frame_id = "map";
00466     new_observation_pose.header.stamp = observation_pose.header.stamp;
00467 
00468     Eigen::Vector2d dir_vec(original_goal_pose - closest_point_world);
00469 
00470     double distance = dir_vec.norm();
00471 
00472     //If we get back the original observation pose (or another one very close to it), return that
00473     if (distance < (costmap_->getResolution() * 1.5)){
00474       new_observation_pose.pose = observation_pose.pose;
00475       new_observation_pose.pose.position.z = 0.0;
00476       ROS_INFO("Observation pose unchanged");
00477     }else{
00478 
00479       if (desired_distance < distance){
00480         new_observation_pose.pose.position.x = closest_point_world.x();
00481         new_observation_pose.pose.position.y = closest_point_world.y();
00482         new_observation_pose.pose.position.z = 0.0;
00483       }else{
00484 
00485         double test_distance = distance;
00486 
00487         Eigen::Vector2d last_valid_pos(closest_point_world);
00488 
00489         do{
00490           test_distance += 0.1;
00491 
00492           double distance_factor = test_distance / distance;
00493 
00494           Eigen::Vector2d new_pos(original_goal_pose - dir_vec*distance_factor);
00495 
00496           unsigned int x, y;
00497           costmap_->worldToMap(new_pos[0], new_pos[1], x, y);
00498           unsigned int idx = costmap_->getIndex(x,y);
00499 
00500           if(!this->isFree(idx)){
00501             break;
00502           }
00503 
00504           last_valid_pos = new_pos;
00505 
00506         }while (test_distance < desired_distance);
00507 
00508         new_observation_pose.pose.position.x = last_valid_pos.x();
00509         new_observation_pose.pose.position.y = last_valid_pos.y();
00510         new_observation_pose.pose.position.z = 0.0;
00511       }
00512 
00513       double angle = std::atan2(dir_vec.y(), dir_vec.x());
00514 
00515       new_observation_pose.pose.orientation.w = cos(angle*0.5);
00516       new_observation_pose.pose.orientation.x = 0.0;
00517       new_observation_pose.pose.orientation.y = 0.0;
00518       new_observation_pose.pose.orientation.z = sin(angle*0.5);
00519       ROS_INFO("Observation pose moved away from wall");
00520     }
00521 
00522     return true;
00523   }else{
00524     // If closest vals are still -1, we didn't find a position
00525     ROS_ERROR("Couldn't find observation pose for given point.");
00526     return false;
00527   }
00528 }
00529 
00530 bool HectorExplorationPlanner::doAlternativeExploration(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &plan, std::vector<geometry_msgs::PoseStamped> &oldplan){
00531   ROS_INFO("[hector_exploration_planner] alternative exploration: starting alternative exploration");
00532 
00533   // setup maps and goals
00534   resetMaps();
00535   plan.clear();
00536 
00537   std::vector<geometry_msgs::PoseStamped> goals;
00538 
00539   std::vector<geometry_msgs::PoseStamped> old_frontier;
00540   old_frontier.push_back(oldplan.back());
00541 
00542   // create obstacle tranform
00543   buildobstacle_trans_array_(p_use_inflated_obs_);
00544 
00545   // search for frontiers
00546   if(findFrontiers(goals,old_frontier)){
00547     ROS_INFO("[hector_exploration_planner] alternative exploration: found %u frontiers!", (unsigned int) goals.size());
00548   } else {
00549     ROS_WARN("[hector_exploration_planner] alternative exploration: no frontiers have been found!");
00550     return false;
00551   }
00552 
00553   // make plan
00554   if(!buildexploration_trans_array_(start,goals,true)){
00555     return false;
00556   }
00557   if(!getTrajectory(start,goals,plan)){
00558     return false;
00559   }
00560 
00561   const geometry_msgs::PoseStamped& this_goal = plan.back();
00562   unsigned int mx,my;
00563   costmap_->worldToMap(this_goal.pose.position.x,this_goal.pose.position.y,mx,my);
00564   previous_goal_ = costmap_->getIndex(mx,my);
00565 
00566   ROS_INFO("[hector_exploration_planner] alternative exploration: plan to a frontier has been found! plansize: %u ", (unsigned int)plan.size());
00567   return true;
00568 }
00569 
00570 float HectorExplorationPlanner::angleDifferenceWall(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal){
00571   // setup start positions
00572   unsigned int mxs,mys;
00573   costmap_->worldToMap(start.pose.position.x,start.pose.position.y,mxs,mys);
00574 
00575   unsigned int gx,gy;
00576   costmap_->worldToMap(goal.pose.position.x,goal.pose.position.y,gx,gy);
00577 
00578   int goal_proj_x = gx-mxs;
00579   int goal_proj_y = gy-mys;
00580 
00581   float start_angle = tf::getYaw(start.pose.orientation);
00582   float goal_angle = std::atan2(goal_proj_y,goal_proj_x);
00583 
00584   float both_angle = 0;
00585   if(start_angle > goal_angle){
00586     both_angle = start_angle - goal_angle;
00587   } else {
00588     both_angle = goal_angle - start_angle;
00589   }
00590 
00591   return both_angle;
00592 }
00593 
00594 bool HectorExplorationPlanner::exploreWalls(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &plan){
00595 
00596   //@TODO: Properly set this parameters
00597   int startExploreWall = 1;
00598 
00599   ROS_DEBUG("[hector_exploration_planner] wall-follow: exploreWalls");
00600   unsigned int mx,my;
00601   if(!costmap_->worldToMap(start.pose.position.x, start.pose.position.y, mx, my)){
00602     ROS_WARN("[hector_exploration_planner] wall-follow: The start coordinates are outside the costmap!");
00603     return false;
00604   }
00605   int currentPoint=costmap_->getIndex(mx, my);
00606   int nextPoint;
00607   int oldDirection = -1;
00608   int k=0;
00609   int loop=0;
00610 
00611   while(k<50){
00612     int adjacentPoints [8];
00613     getAdjacentPoints(currentPoint, adjacentPoints);
00614     int dirPoints [3];
00615 
00616     unsigned int minDelta = UINT_MAX;
00617     unsigned int maxDelta = 0;
00618     unsigned int thisDelta;
00619     float minAngle=3.1415; //Rad -> 180°
00620 
00621     geometry_msgs::PoseStamped trajPoint;
00622     unsigned int gx,gy;
00623 
00624     if(oldDirection==-1){
00625       // find robot orientation
00626       for ( int i=0; i<8; i++){
00627         costmap_->indexToCells((unsigned int)adjacentPoints[i],gx,gy);
00628         double wx,wy;
00629         costmap_->mapToWorld(gx,gy,wx,wy);
00630         std::string global_frame = costmap_ros_->getGlobalFrameID();
00631         trajPoint.header.frame_id = global_frame;
00632         trajPoint.pose.position.x = wx;
00633         trajPoint.pose.position.y = wy;
00634         trajPoint.pose.position.z = 0.0;
00635         float yaw = angleDifferenceWall(start, trajPoint);
00636         if(yaw < minAngle){
00637           minAngle=yaw;
00638           oldDirection=i;
00639         }
00640       }
00641     }
00642 
00643     //search possible orientation
00644 
00645     if (oldDirection == 0){
00646       dirPoints[0]=oldDirection+4; //right-forward
00647       dirPoints[1]=oldDirection;   //forward
00648       dirPoints[2]=oldDirection+7; //left-forward
00649     }
00650     else if (oldDirection < 3){
00651       dirPoints[0]=oldDirection+4;
00652       dirPoints[1]=oldDirection;
00653       dirPoints[2]=oldDirection+3;
00654     }
00655     else if (oldDirection == 3){
00656       dirPoints[0]=oldDirection+4;
00657       dirPoints[1]=oldDirection;
00658       dirPoints[2]=oldDirection+3;
00659     }
00660     else if (oldDirection == 4){
00661       dirPoints[0]=oldDirection-3;
00662       dirPoints[1]=oldDirection;
00663       dirPoints[2]=oldDirection-4;
00664     }
00665     else if (oldDirection < 7){
00666       dirPoints[0]=oldDirection-3;
00667       dirPoints[1]=oldDirection;
00668       dirPoints[2]=oldDirection-4;
00669     }
00670     else if (oldDirection == 7){
00671       dirPoints[0]=oldDirection-7;
00672       dirPoints[1]=oldDirection;
00673       dirPoints[2]=oldDirection-4;
00674     }
00675 
00676     // decide LHR or RHR
00677     if(startExploreWall == -1){
00678       if(obstacle_trans_array_[adjacentPoints[dirPoints[0]]] <= obstacle_trans_array_[adjacentPoints[dirPoints[2]]]){
00679         startExploreWall = 0;
00680         ROS_INFO("[hector_exploration_planner] wall-follow: RHR");//mirror inverted??
00681       }
00682       else {
00683         startExploreWall = 1;
00684         ROS_INFO("[hector_exploration_planner] wall-follow: LHR");//mirror inverted??
00685       }
00686     }
00687 
00688 
00689 
00690     //switch left and right, LHR
00691     if(startExploreWall == 1){
00692       int temp=dirPoints[0];
00693       dirPoints[0]=dirPoints[2];
00694       dirPoints[2]=temp;
00695     }
00696 
00697 
00698     // find next point
00699     int t=0;
00700     for(int i=0; i<3; i++){
00701       thisDelta = obstacle_trans_array_[adjacentPoints[dirPoints[i]]];
00702 
00703       if (thisDelta > 3000 || loop > 7) // point is unknown or robot drive loop
00704       {
00705         int plansize = plan.size() - 4;
00706         if(plansize > 0 ){
00707           plan.resize(plansize);
00708         }
00709         ROS_DEBUG("[hector_exploration_planner] wall-follow: END: exploreWalls. Plansize %d", (int)plan.size());
00710         return !plan.empty();
00711       }
00712 
00713       if(thisDelta >= (unsigned int) p_min_obstacle_dist_){
00714         if(obstacle_trans_array_[currentPoint] >= (unsigned int) p_min_obstacle_dist_){
00715           if(abs(thisDelta - p_min_obstacle_dist_) < minDelta){
00716             minDelta = abs(thisDelta - p_min_obstacle_dist_);
00717             nextPoint = adjacentPoints[dirPoints[i]];
00718             oldDirection = dirPoints[i];
00719           }
00720         }
00721         if(obstacle_trans_array_[currentPoint] < (unsigned int) p_min_obstacle_dist_){
00722           if(thisDelta > maxDelta){
00723             maxDelta = thisDelta;
00724             nextPoint = adjacentPoints[dirPoints[i]];
00725             oldDirection = dirPoints[i];
00726           }
00727         }
00728       }
00729       else {
00730         if(thisDelta < obstacle_trans_array_[currentPoint]){
00731           t++;
00732         }
00733         if(thisDelta > maxDelta){
00734           maxDelta = thisDelta;
00735           nextPoint = adjacentPoints[dirPoints[i]];
00736           oldDirection = dirPoints[i];
00737 
00738         }
00739       }
00740     }
00741 
00742     if(t==3 && abs(obstacle_trans_array_[adjacentPoints[dirPoints[0]]] - obstacle_trans_array_[adjacentPoints[dirPoints[1]]]) < STRAIGHT_COST
00743     && abs(obstacle_trans_array_[adjacentPoints[dirPoints[0]]] - obstacle_trans_array_[adjacentPoints[dirPoints[2]]]) < STRAIGHT_COST
00744     && abs(obstacle_trans_array_[adjacentPoints[dirPoints[1]]] - obstacle_trans_array_[adjacentPoints[dirPoints[2]]]) < STRAIGHT_COST){
00745       nextPoint=adjacentPoints[dirPoints[2]];
00746       oldDirection=dirPoints[2];
00747     }
00748 
00749     if(oldDirection==dirPoints[2])
00750       loop++;
00751     else
00752       loop=0;
00753 
00754     // add point
00755     unsigned int sx,sy;
00756     costmap_->indexToCells((unsigned int)currentPoint,sx,sy);
00757     costmap_->indexToCells((unsigned int)nextPoint,gx,gy);
00758     double wx,wy;
00759     costmap_->mapToWorld(sx,sy,wx,wy);
00760     std::string global_frame = costmap_ros_->getGlobalFrameID();
00761     trajPoint.header.frame_id = global_frame;
00762     trajPoint.pose.position.x = wx;
00763     trajPoint.pose.position.y = wy;
00764     trajPoint.pose.position.z = 0.0;
00765     // assign orientation
00766     int dx = gx-sx;
00767     int dy = gy-sy;
00768     double yaw_path = std::atan2(dy,dx);
00769     trajPoint.pose.orientation.x = 0.0;
00770     trajPoint.pose.orientation.y = 0.0;
00771     trajPoint.pose.orientation.z = sin(yaw_path*0.5f);
00772     trajPoint.pose.orientation.w = cos(yaw_path*0.5f);
00773     plan.push_back(trajPoint);
00774 
00775     currentPoint=nextPoint;
00776     k++;
00777   }
00778   ROS_DEBUG("[hector_exploration_planner] wall-follow: END: exploreWalls. Plansize %d", (int)plan.size());
00779   return !plan.empty();
00780 }
00781 
00782 void HectorExplorationPlanner::setupMapData()
00783 {
00784 
00785 #ifdef COSTMAP_2D_LAYERED_COSTMAP_H_
00786   costmap_ = costmap_ros_->getCostmap();
00787 #else
00788   if (costmap_) delete costmap_;
00789   costmap_ = new costmap_2d::Costmap2D;
00790   costmap_ros_->getCostmapCopy(*costmap_);
00791 #endif
00792 
00793   //Below code can be used to guarantee start pose is cleared. Somewhat risky.
00794   //@TODO: Make available through dynamic reconfigure
00795   /*
00796   std::vector<geometry_msgs::Point> points;
00797   costmap_ros_->getOrientedFootprint(points);
00798 
00799   bool filled = costmap_->setConvexPolygonCost(points, costmap_2d::FREE_SPACE);
00800 
00801   //std::vector<geometry_msgs::Point> points = costmap_ros_->getRobotFootprint();
00802   for (size_t i = 0; i < points.size(); ++i)
00803     std::cout << points[i];
00804   if (filled)
00805     ROS_INFO("Set costmap to free");
00806   else
00807     ROS_INFO("Failed to set costmap free");
00808   */
00809 
00810   if ((this->map_width_ != costmap_->getSizeInCellsX()) || (this->map_height_ != costmap_->getSizeInCellsY())){
00811     map_width_ = costmap_->getSizeInCellsX();
00812     map_height_ = costmap_->getSizeInCellsY();
00813     num_map_cells_ = map_width_ * map_height_;
00814 
00815     // initialize exploration_trans_array_, obstacle_trans_array_, goalMap and frontier_map_array_
00816     exploration_trans_array_.reset(new unsigned int[num_map_cells_]);
00817     obstacle_trans_array_.reset(new unsigned int[num_map_cells_]);
00818     is_goal_array_.reset(new bool[num_map_cells_]);
00819     frontier_map_array_.reset(new int[num_map_cells_]);
00820     clearFrontiers();
00821     resetMaps();
00822   }
00823 
00824   occupancy_grid_array_ = costmap_->getCharMap();
00825 }
00826 
00827 void HectorExplorationPlanner::deleteMapData()
00828 {
00829   exploration_trans_array_.reset();
00830   obstacle_trans_array_.reset();
00831   is_goal_array_.reset();
00832   frontier_map_array_.reset();
00833 }
00834 
00835 
00836 bool HectorExplorationPlanner::buildexploration_trans_array_(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> goals, bool useAnglePenalty, bool use_cell_danger){
00837 
00838   ROS_DEBUG("[hector_exploration_planner] buildexploration_trans_array_");
00839 
00840   // reset exploration transform
00841   std::fill_n(exploration_trans_array_.get(), num_map_cells_, UINT_MAX);
00842   std::fill_n(is_goal_array_.get(), num_map_cells_, false);
00843 
00844   std::queue<int> myqueue;
00845 
00846   size_t num_free_goals = 0;
00847 
00848   // initialize goals
00849   for(unsigned int i = 0; i < goals.size(); ++i){
00850     // setup goal positions
00851     unsigned int mx,my;
00852 
00853     if(!costmap_->worldToMap(goals[i].pose.position.x,goals[i].pose.position.y,mx,my)){
00854       //ROS_WARN("[hector_exploration_planner] The goal coordinates are outside the costmap!");
00855       continue;
00856     }
00857 
00858     int goal_point = costmap_->getIndex(mx,my);
00859 
00860     // Ignore free goal for the moment, check after iterating over all goals if there is not valid one at all
00861     if(!isFree(goal_point)){
00862       continue;
00863     }else{
00864       ++num_free_goals;
00865     }
00866 
00867     unsigned int init_cost = 0;
00868     if(false){
00869       init_cost = angleDanger(angleDifference(start,goals[i])) * getDistanceWeight(start,goals[i]);
00870     }
00871 
00872     exploration_trans_array_[goal_point] = init_cost;
00873 
00874     // do not punish previous frontiers (oscillation)
00875     if(false && isValid(previous_goal_)){
00876       if(isSameFrontier(goal_point, previous_goal_)){
00877         ROS_DEBUG("[hector_exploration_planner] same frontier: init with 0");
00878         exploration_trans_array_[goal_point] = 0;
00879       }
00880     }
00881 
00882     ROS_DEBUG("[hector_exploration_planner] Goal init cost: %d, point: %d", exploration_trans_array_[goal_point], goal_point);
00883     is_goal_array_[goal_point] = true;
00884     myqueue.push(goal_point);
00885   }
00886 
00887   if (num_free_goals == 0){
00888     ROS_WARN("[hector_exploration_planner] All goal coordinates for exploration transform invalid (occupied or out of bounds), aborting.");
00889     return false;
00890   }
00891 
00892   // exploration transform algorithm
00893   if (use_cell_danger){
00894     while(myqueue.size()){
00895       int point = myqueue.front();
00896       myqueue.pop();
00897 
00898       unsigned int minimum = exploration_trans_array_[point];
00899 
00900       int straightPoints[4];
00901       getStraightPoints(point,straightPoints);
00902       int diagonalPoints[4];
00903       getDiagonalPoints(point,diagonalPoints);
00904 
00905       // calculate the minimum exploration value of all adjacent cells
00906       for (int i = 0; i < 4; ++i) {
00907         if (isFree(straightPoints[i])) {
00908           unsigned int neighbor_cost = minimum + STRAIGHT_COST + cellDanger(straightPoints[i]);
00909 
00910           if (exploration_trans_array_[straightPoints[i]] > neighbor_cost) {
00911             exploration_trans_array_[straightPoints[i]] = neighbor_cost;
00912             myqueue.push(straightPoints[i]);
00913           }
00914         }
00915 
00916         if (isFree(diagonalPoints[i])) {
00917           unsigned int neighbor_cost = minimum + DIAGONAL_COST + cellDanger(diagonalPoints[i]);
00918 
00919           if (exploration_trans_array_[diagonalPoints[i]] > neighbor_cost) {
00920             exploration_trans_array_[diagonalPoints[i]] = neighbor_cost;
00921             myqueue.push(diagonalPoints[i]);
00922           }
00923         }
00924       }
00925     }
00926   }else{
00927     while(myqueue.size()){
00928       int point = myqueue.front();
00929       myqueue.pop();
00930 
00931       unsigned int minimum = exploration_trans_array_[point];
00932 
00933       int straightPoints[4];
00934       getStraightPoints(point,straightPoints);
00935       int diagonalPoints[4];
00936       getDiagonalPoints(point,diagonalPoints);
00937 
00938       // calculate the minimum exploration value of all adjacent cells
00939       for (int i = 0; i < 4; ++i) {
00940         if (isFree(straightPoints[i])) {
00941           unsigned int neighbor_cost = minimum + STRAIGHT_COST;
00942 
00943           if (exploration_trans_array_[straightPoints[i]] > neighbor_cost) {
00944             exploration_trans_array_[straightPoints[i]] = neighbor_cost;
00945             myqueue.push(straightPoints[i]);
00946           }
00947         }
00948 
00949         if (isFree(diagonalPoints[i])) {
00950           unsigned int neighbor_cost = minimum + DIAGONAL_COST;
00951 
00952           if (exploration_trans_array_[diagonalPoints[i]] > neighbor_cost) {
00953             exploration_trans_array_[diagonalPoints[i]] = neighbor_cost;
00954             myqueue.push(diagonalPoints[i]);
00955           }
00956         }
00957       }
00958     }
00959   }
00960 
00961   ROS_DEBUG("[hector_exploration_planner] END: buildexploration_trans_array_");
00962 
00963   vis_->publishVisOnDemand(*costmap_, exploration_trans_array_.get());
00964   return true;
00965 }
00966 
00967 bool HectorExplorationPlanner::buildobstacle_trans_array_(bool use_inflated_obstacles){
00968   ROS_DEBUG("[hector_exploration_planner] buildobstacle_trans_array_");
00969   std::queue<int> myqueue;
00970 
00971   // init obstacles
00972   for(unsigned int i=0; i < num_map_cells_; ++i){
00973     if(occupancy_grid_array_[i] == costmap_2d::LETHAL_OBSTACLE){
00974       myqueue.push(i);
00975       obstacle_trans_array_[i] = 0;
00976     } else if(use_inflated_obstacles){
00977       if(occupancy_grid_array_[i] == costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
00978         myqueue.push(i);
00979         obstacle_trans_array_[i] = 0;
00980       }
00981     }
00982   }
00983 
00984   unsigned int obstacle_cutoff_value = static_cast<unsigned int>((p_obstacle_cutoff_dist_ / costmap_->getResolution()) * STRAIGHT_COST + 0.5);
00985 
00986   // obstacle transform algorithm
00987   while(myqueue.size()){
00988     int point = myqueue.front();
00989     myqueue.pop();
00990 
00991     unsigned int minimum = obstacle_trans_array_[point];
00992     if (minimum > obstacle_cutoff_value) continue;
00993 
00994     int straightPoints[4];
00995     getStraightPoints(point,straightPoints);
00996     int diagonalPoints[4];
00997     getDiagonalPoints(point,diagonalPoints);
00998 
00999     // check all 8 directions
01000     for(int i = 0; i < 4; ++i){
01001       if (isValid(straightPoints[i]) && (obstacle_trans_array_[straightPoints[i]] > minimum + STRAIGHT_COST)) {
01002         obstacle_trans_array_[straightPoints[i]] = minimum + STRAIGHT_COST;
01003         myqueue.push(straightPoints[i]);
01004       }
01005       if (isValid(diagonalPoints[i]) && (obstacle_trans_array_[diagonalPoints[i]] > minimum + DIAGONAL_COST)) {
01006         obstacle_trans_array_[diagonalPoints[i]] = minimum + DIAGONAL_COST;
01007         myqueue.push(diagonalPoints[i]);
01008       }
01009     }
01010   }
01011 
01012   ROS_DEBUG("[hector_exploration_planner] END: buildobstacle_trans_array_");
01013 
01014   obstacle_vis_->publishVisOnDemand(*costmap_, obstacle_trans_array_.get());
01015   return true;
01016 }
01017 
01018 bool HectorExplorationPlanner::getTrajectory(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> goals, std::vector<geometry_msgs::PoseStamped> &plan){
01019 
01020   ROS_DEBUG("[hector_exploration_planner] getTrajectory");
01021 
01022   // setup start positions
01023   unsigned int mx,my;
01024 
01025   if(!costmap_->worldToMap(start.pose.position.x,start.pose.position.y,mx,my)){
01026     ROS_WARN("[hector_exploration_planner] The start coordinates are outside the costmap!");
01027     return false;
01028   }
01029 
01030   int currentPoint = costmap_->getIndex(mx,my);
01031   int nextPoint = currentPoint;
01032 
01033 
01034 
01035   geometry_msgs::PoseStamped trajPoint;
01036   std::string global_frame = costmap_ros_->getGlobalFrameID();
01037   trajPoint.header.frame_id = global_frame;
01038 
01039   if (is_goal_array_[currentPoint]){
01040     ROS_INFO("Already at goal point position. No pose vector generated.");
01041     return true;
01042   }
01043 
01044   while(!is_goal_array_[currentPoint]){
01045     int thisDelta;
01046     int adjacentPoints[8];
01047     getAdjacentPoints(currentPoint,adjacentPoints);
01048 
01049     int maxDelta = 0;
01050 
01051     for(int i = 0; i < 8; ++i){
01052       if(isFree(adjacentPoints[i])){
01053         thisDelta = exploration_trans_array_[currentPoint] - exploration_trans_array_[adjacentPoints[i]];
01054         if(thisDelta > maxDelta){
01055           maxDelta = thisDelta;
01056           nextPoint = adjacentPoints[i];
01057         }
01058       }
01059     }
01060 
01061     // This happens when there is no valid exploration transform data at the start point for example
01062     if(maxDelta == 0){
01063       ROS_WARN("[hector_exploration_planner] No path to the goal could be found by following gradient!");
01064       return false;
01065     }
01066 
01067 
01068     // make trajectory point
01069     unsigned int sx,sy,gx,gy;
01070     costmap_->indexToCells((unsigned int)currentPoint,sx,sy);
01071     costmap_->indexToCells((unsigned int)nextPoint,gx,gy);
01072     double wx,wy;
01073     costmap_->mapToWorld(sx,sy,wx,wy);
01074 
01075     trajPoint.pose.position.x = wx;
01076     trajPoint.pose.position.y = wy;
01077     trajPoint.pose.position.z = 0.0;
01078 
01079     // assign orientation
01080     int dx = gx-sx;
01081     int dy = gy-sy;
01082     double yaw_path = std::atan2(dy,dx);
01083     trajPoint.pose.orientation.x = 0.0;
01084     trajPoint.pose.orientation.y = 0.0;
01085     trajPoint.pose.orientation.z = sin(yaw_path*0.5f);
01086     trajPoint.pose.orientation.w = cos(yaw_path*0.5f);
01087 
01088     plan.push_back(trajPoint);
01089 
01090     currentPoint = nextPoint;
01091     maxDelta = 0;
01092   }
01093 
01094   ROS_DEBUG("[hector_exploration_planner] END: getTrajectory. Plansize %u", (unsigned int)plan.size());
01095   return !plan.empty();
01096 }
01097 
01098 bool HectorExplorationPlanner::findFrontiers(std::vector<geometry_msgs::PoseStamped> &frontiers){
01099   std::vector<geometry_msgs::PoseStamped> empty_vec;
01100   return findFrontiers(frontiers,empty_vec);
01101 }
01102 
01103 /*
01104  * searches the occupancy grid for frontier cells and merges them into one target point per frontier.
01105  * The returned frontiers are in world coordinates.
01106  */
01107 bool HectorExplorationPlanner::findFrontiersCloseToPath(std::vector<geometry_msgs::PoseStamped> &frontiers){
01108 
01109   clearFrontiers();
01110   frontiers.clear();
01111 
01112   // get the trajectory as seeds for the exploration transform
01113   hector_nav_msgs::GetRobotTrajectory srv_path;
01114   if (path_service_client_.call(srv_path)){
01115 
01116     std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
01117 
01118     // We push poses of the travelled trajectory to the goals vector for building the exploration transform
01119     std::vector<geometry_msgs::PoseStamped> goals;
01120 
01121     size_t size = traj_vector.size();
01122     ROS_INFO("[hector_exploration_planner] Size of trajectory vector for close exploration %u", (unsigned int)size);
01123 
01124     if(size > 0){
01125       geometry_msgs::PoseStamped lastPose = traj_vector[size-1];
01126       goals.push_back(lastPose);
01127 
01128       if (size > 1){
01129 
01130         for(int i = static_cast<int>(size-2); i >= 0; --i){
01131           const geometry_msgs::PoseStamped& pose = traj_vector[i];
01132           unsigned int x,y;
01133           costmap_->worldToMap(pose.pose.position.x,pose.pose.position.y,x,y);
01134           unsigned int m_point = costmap_->getIndex(x,y);
01135 
01136           double dx = lastPose.pose.position.x - pose.pose.position.x;
01137           double dy = lastPose.pose.position.y - pose.pose.position.y;
01138 
01139           if((dx*dx) + (dy*dy) > (0.25*0.25)){
01140             goals.push_back(pose);
01141             lastPose = pose;
01142           }
01143         }
01144 
01145         ROS_INFO("[hector_exploration_planner] pushed %u goals (trajectory) for close to robot frontier search", (unsigned int)goals.size());
01146 
01147         // make exploration transform
01148         tf::Stamped<tf::Pose> robotPose;
01149         if(!costmap_ros_->getRobotPose(robotPose)){
01150           ROS_WARN("[hector_exploration_planner]: Failed to get RobotPose");
01151         }
01152         geometry_msgs::PoseStamped robotPoseMsg;
01153         tf::poseStampedTFToMsg(robotPose, robotPoseMsg);
01154 
01155         if (!buildexploration_trans_array_(robotPoseMsg, goals, false, false)){
01156           ROS_WARN("[hector_exploration_planner]: Creating exploration transform array in find inner frontier failed, aborting.");
01157           return false;
01158         }
01159 
01160         close_path_vis_->publishVisOnDemand(*costmap_, exploration_trans_array_.get());
01161 
01162         unsigned int explore_threshold = static_cast<unsigned int> (static_cast<double>(STRAIGHT_COST) * (1.0/costmap_->getResolution()) * p_close_to_path_target_distance_);
01163 
01164         //std::vector<geometry_msgs::PoseStamped> close_frontiers;
01165 
01166         for(unsigned int i = 0; i < num_map_cells_; ++i){
01167 
01168           unsigned int current_val = exploration_trans_array_[i];
01169 
01170           if(current_val < UINT_MAX){
01171 
01172             if (current_val >= explore_threshold){ //&& current_val <= explore_threshold+ DIAGONAL_COST){
01173               geometry_msgs::PoseStamped finalFrontier;
01174               double wx,wy;
01175               unsigned int mx,my;
01176               costmap_->indexToCells(i, mx, my);
01177               costmap_->mapToWorld(mx,my,wx,wy);
01178               std::string global_frame = costmap_ros_->getGlobalFrameID();
01179               finalFrontier.header.frame_id = global_frame;
01180               finalFrontier.pose.position.x = wx;
01181               finalFrontier.pose.position.y = wy;
01182               finalFrontier.pose.position.z = 0.0;
01183 
01184               double yaw = getYawToUnknown(costmap_->getIndex(mx,my));
01185 
01186               //if(frontier_is_valid){
01187 
01188               finalFrontier.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
01189 
01190               frontiers.push_back(finalFrontier);
01191 
01192             }
01193 
01194           }
01195         }
01196 
01197         return frontiers.size() > 0;
01198 
01199 
01200 
01201 
01202 
01203       }
01204     }
01205   }
01206 
01207 
01208 
01209 
01210 
01211   // list of all frontiers in the occupancy grid
01212   std::vector<int> allFrontiers;
01213 
01214   // check for all cells in the occupancy grid whether or not they are frontier cells
01215   for(unsigned int i = 0; i < num_map_cells_; ++i){
01216     if(isFrontier(i)){
01217       allFrontiers.push_back(i);
01218     }
01219   }
01220 
01221   for(unsigned int i = 0; i < allFrontiers.size(); ++i){
01222     if(!isFrontierReached(allFrontiers[i])){
01223       geometry_msgs::PoseStamped finalFrontier;
01224       double wx,wy;
01225       unsigned int mx,my;
01226       costmap_->indexToCells(allFrontiers[i], mx, my);
01227       costmap_->mapToWorld(mx,my,wx,wy);
01228       std::string global_frame = costmap_ros_->getGlobalFrameID();
01229       finalFrontier.header.frame_id = global_frame;
01230       finalFrontier.pose.position.x = wx;
01231       finalFrontier.pose.position.y = wy;
01232       finalFrontier.pose.position.z = 0.0;
01233 
01234       double yaw = getYawToUnknown(costmap_->getIndex(mx,my));
01235 
01236       //if(frontier_is_valid){
01237 
01238       finalFrontier.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
01239 
01240       frontiers.push_back(finalFrontier);
01241     }
01242     //}
01243   }
01244 
01245   return (frontiers.size() > 0);
01246 }
01247 
01248 /*
01249  * searches the occupancy grid for frontier cells and merges them into one target point per frontier.
01250  * The returned frontiers are in world coordinates.
01251  */
01252 bool HectorExplorationPlanner::findFrontiers(std::vector<geometry_msgs::PoseStamped> &frontiers, std::vector<geometry_msgs::PoseStamped> &noFrontiers){
01253 
01254   // get latest costmap
01255   clearFrontiers();
01256 
01257   // list of all frontiers in the occupancy grid
01258   std::vector<int> allFrontiers;
01259 
01260   // check for all cells in the occupancy grid whether or not they are frontier cells
01261   for(unsigned int i = 0; i < num_map_cells_; ++i){
01262     if(isFrontier(i)){
01263       allFrontiers.push_back(i);
01264     }
01265   }
01266 
01267   for(unsigned int i = 0; i < allFrontiers.size(); ++i){
01268     if(!isFrontierReached(allFrontiers[i])){
01269       geometry_msgs::PoseStamped finalFrontier;
01270       double wx,wy;
01271       unsigned int mx,my;
01272       costmap_->indexToCells(allFrontiers[i], mx, my);
01273       costmap_->mapToWorld(mx,my,wx,wy);
01274       std::string global_frame = costmap_ros_->getGlobalFrameID();
01275       finalFrontier.header.frame_id = global_frame;
01276       finalFrontier.pose.position.x = wx;
01277       finalFrontier.pose.position.y = wy;
01278       finalFrontier.pose.position.z = 0.0;
01279 
01280       double yaw = getYawToUnknown(costmap_->getIndex(mx,my));
01281 
01282       //if(frontier_is_valid){
01283 
01284       finalFrontier.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
01285 
01286       frontiers.push_back(finalFrontier);
01287     }
01288     //}
01289   }
01290 
01291   return (frontiers.size() > 0);
01292 
01293   //@TODO: Review and possibly remove unused code below
01294 
01295   // value of the next blob
01296   int nextBlobValue = 1;
01297   std::list<int> usedBlobs;
01298 
01299   for(unsigned int i = 0; i < allFrontiers.size(); ++i){
01300 
01301     // get all adjacent blobs to the current frontier point
01302     int currentPoint = allFrontiers[i];
01303     int adjacentPoints[8];
01304     getAdjacentPoints(currentPoint,adjacentPoints);
01305 
01306     std::list<int> blobs;
01307 
01308     for(int j = 0; j < 8; j++){
01309       if(isValid(adjacentPoints[j]) && (frontier_map_array_[adjacentPoints[j]] > 0)){
01310         blobs.push_back(frontier_map_array_[adjacentPoints[j]]);
01311       }
01312     }
01313     blobs.unique();
01314 
01315     if(blobs.empty()){
01316       // create new blob
01317       frontier_map_array_[currentPoint] = nextBlobValue;
01318       usedBlobs.push_back(nextBlobValue);
01319       nextBlobValue++;
01320     } else {
01321       // merge all found blobs
01322       int blobMergeVal = 0;
01323 
01324       for(std::list<int>::iterator adjBlob = blobs.begin(); adjBlob != blobs.end(); ++adjBlob){
01325         if(adjBlob == blobs.begin()){
01326           blobMergeVal = *adjBlob;
01327           frontier_map_array_[currentPoint] = blobMergeVal;
01328         } else {
01329 
01330           for(unsigned int k = 0; k < allFrontiers.size(); k++){
01331             if(frontier_map_array_[allFrontiers[k]] == *adjBlob){
01332               usedBlobs.remove(*adjBlob);
01333               frontier_map_array_[allFrontiers[k]] = blobMergeVal;
01334             }
01335           }
01336         }
01337       }
01338     }
01339   }
01340 
01341   int id = 1;
01342 
01343   bool visualization_requested = (visualization_pub_.getNumSubscribers() > 0);
01344 
01345   // summarize every blob into a single point (maximum obstacle_trans_array_ value)
01346   for(std::list<int>::iterator currentBlob = usedBlobs.begin(); currentBlob != usedBlobs.end(); ++currentBlob){
01347     int current_frontier_size = 0;
01348     int max_obs_idx = 0;
01349 
01350     for(unsigned int i = 0; i < allFrontiers.size(); ++i){
01351       int point = allFrontiers[i];
01352 
01353       if(frontier_map_array_[point] == *currentBlob){
01354         current_frontier_size++;
01355         if(obstacle_trans_array_[point] > obstacle_trans_array_[allFrontiers[max_obs_idx]]){
01356           max_obs_idx = i;
01357         }
01358       }
01359     }
01360 
01361     if(current_frontier_size < p_min_frontier_size_){
01362       continue;
01363     }
01364 
01365     int frontier_point = allFrontiers[max_obs_idx];
01366     unsigned int x,y;
01367     costmap_->indexToCells(frontier_point,x,y);
01368 
01369     // check if frontier is valid (not to close to robot and not in noFrontiers vector
01370     bool frontier_is_valid = true;
01371 
01372     if(isFrontierReached(frontier_point)){
01373       frontier_is_valid = false;
01374     }
01375 
01376     for(size_t i = 0; i < noFrontiers.size(); ++i){
01377       const geometry_msgs::PoseStamped& noFrontier = noFrontiers[i];
01378       unsigned int mx,my;
01379       costmap_->worldToMap(noFrontier.pose.position.x,noFrontier.pose.position.y,mx,my);
01380       int no_frontier_point = costmap_->getIndex(x,y);
01381       if(isSameFrontier(frontier_point,no_frontier_point)){
01382         frontier_is_valid = false;
01383       }
01384     }
01385 
01386     geometry_msgs::PoseStamped finalFrontier;
01387     double wx,wy;
01388     costmap_->mapToWorld(x,y,wx,wy);
01389     std::string global_frame = costmap_ros_->getGlobalFrameID();
01390     finalFrontier.header.frame_id = global_frame;
01391     finalFrontier.pose.position.x = wx;
01392     finalFrontier.pose.position.y = wy;
01393     finalFrontier.pose.position.z = 0.0;
01394 
01395     double yaw = getYawToUnknown(costmap_->getIndex(x,y));
01396 
01397     if(frontier_is_valid){
01398 
01399       finalFrontier.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
01400       frontiers.push_back(finalFrontier);
01401     }
01402 
01403     // visualization (export to method?)
01404     if(visualization_requested){
01405       visualization_msgs::Marker marker;
01406       marker.header.frame_id = "map";
01407       marker.header.stamp = ros::Time();
01408       marker.ns = "hector_exploration_planner";
01409       marker.id = id++;
01410       marker.type = visualization_msgs::Marker::ARROW;
01411       marker.action = visualization_msgs::Marker::ADD;
01412       marker.pose.position.x = wx;
01413       marker.pose.position.y = wy;
01414       marker.pose.position.z = 0.0;
01415       marker.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
01416       marker.scale.x = 0.2;
01417       marker.scale.y = 0.2;
01418       marker.scale.z = 0.2;
01419       marker.color.a = 1.0;
01420 
01421       if(frontier_is_valid){
01422         marker.color.r = 0.0;
01423         marker.color.g = 1.0;
01424       }else{
01425         marker.color.r = 1.0;
01426         marker.color.g = 0.0;
01427       }
01428 
01429       marker.color.b = 0.0;
01430       marker.lifetime = ros::Duration(5,0);
01431       visualization_pub_.publish(marker);
01432     }
01433 
01434   }
01435   return !frontiers.empty();
01436 }
01437 
01438 bool HectorExplorationPlanner::findInnerFrontier(std::vector<geometry_msgs::PoseStamped> &innerFrontier){
01439   clearFrontiers();
01440 
01441   // get the trajectory as seeds for the exploration transform
01442   hector_nav_msgs::GetRobotTrajectory srv_path;
01443   if (path_service_client_.call(srv_path)){
01444 
01445     std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
01446 
01447     // We push poses of the travelled trajectory to the goals vector for building the exploration transform
01448     std::vector<geometry_msgs::PoseStamped> goals;
01449 
01450     size_t size = traj_vector.size();
01451     ROS_DEBUG("[hector_exploration_planner] size of trajectory vector %u", (unsigned int)size);
01452 
01453     if(size > 0){
01454       geometry_msgs::PoseStamped lastPose = traj_vector[size-1];
01455       goals.push_back(lastPose);
01456 
01457       if (size > 1){
01458 
01459         // Allow collision at start in case vehicle is (very) close to wall
01460         bool collision_allowed = true;
01461 
01462         for(int i = static_cast<int>(size-2); i >= 0; --i){
01463           const geometry_msgs::PoseStamped& pose = traj_vector[i];
01464           unsigned int x,y;
01465           costmap_->worldToMap(pose.pose.position.x,pose.pose.position.y,x,y);
01466           unsigned int m_point = costmap_->getIndex(x,y);
01467 
01468           double dx = lastPose.pose.position.x - pose.pose.position.x;
01469           double dy = lastPose.pose.position.y - pose.pose.position.y;
01470 
01471           bool point_in_free_space = isFreeFrontiers(m_point);
01472 
01473           // extract points with 0.5m distance (if free)
01474           if(point_in_free_space){
01475             if((dx*dx) + (dy*dy) > (0.25*0.25)){
01476               goals.push_back(pose);
01477               lastPose = pose;
01478               collision_allowed = false;
01479             }
01480           }
01481 
01482           if (!point_in_free_space && !collision_allowed){
01483             break;
01484           }
01485         }
01486       }
01487 
01488 
01489       ROS_DEBUG("[hector_exploration_planner] pushed %u goals (trajectory) for inner frontier-search", (unsigned int)goals.size());
01490 
01491       // make exploration transform
01492       tf::Stamped<tf::Pose> robotPose;
01493       if(!costmap_ros_->getRobotPose(robotPose)){
01494         ROS_WARN("[hector_exploration_planner]: Failed to get RobotPose");
01495       }
01496       geometry_msgs::PoseStamped robotPoseMsg;
01497       tf::poseStampedTFToMsg(robotPose, robotPoseMsg);
01498 
01499       if (!buildexploration_trans_array_(robotPoseMsg, goals, false)){
01500         ROS_WARN("[hector_exploration_planner]: Creating exploration transform array in find inner frontier failed, aborting.");
01501         return false;
01502       }
01503 
01504       inner_vis_->publishVisOnDemand(*costmap_, exploration_trans_array_.get());
01505 
01506       unsigned int x,y;
01507       costmap_->worldToMap(robotPoseMsg.pose.position.x,robotPoseMsg.pose.position.y,x,y);
01508 
01509 
01510 
01511 
01512       // get point with maximal distance to trajectory
01513       int max_exploration_trans_point = -1;
01514       unsigned int max_exploration_trans_val = 0;
01515 
01516       for(unsigned int i = 0; i < num_map_cells_; ++i){
01517 
01518         if(exploration_trans_array_[i] < UINT_MAX){
01519           if(exploration_trans_array_[i] > max_exploration_trans_val){
01520             if(!isFrontierReached(i)){
01521               max_exploration_trans_point = i;
01522               max_exploration_trans_val = exploration_trans_array_[i];
01523             }
01524           }
01525         }
01526       }
01527 
01528       if (max_exploration_trans_point == 0){
01529         ROS_WARN("[hector_exploration_planner]: Couldn't find max exploration transform point for inner exploration, aborting.");
01530         return false;
01531       }
01532 
01533       geometry_msgs::PoseStamped finalFrontier;
01534       unsigned int fx,fy;
01535       double wfx,wfy;
01536       costmap_->indexToCells(max_exploration_trans_point,fx,fy);
01537       costmap_->mapToWorld(fx,fy,wfx,wfy);
01538       std::string global_frame = costmap_ros_->getGlobalFrameID();
01539       finalFrontier.header.frame_id = global_frame;
01540       finalFrontier.pose.position.x = wfx;
01541       finalFrontier.pose.position.y = wfy;
01542       finalFrontier.pose.position.z = 0.0;
01543 
01544       // assign orientation
01545       int dx = fx-x;
01546       int dy = fy-y;
01547       double yaw_path = std::atan2(dy,dx);
01548       finalFrontier.pose.orientation.x = 0.0;
01549       finalFrontier.pose.orientation.y = 0.0;
01550       finalFrontier.pose.orientation.z = sin(yaw_path*0.5f);
01551       finalFrontier.pose.orientation.w = cos(yaw_path*0.5f);
01552 
01553       innerFrontier.push_back(finalFrontier);
01554 
01555       if(visualization_pub_.getNumSubscribers() > 0){
01556         visualization_msgs::Marker marker;
01557         marker.header.frame_id = "map";
01558         marker.header.stamp = ros::Time();
01559         marker.ns = "hector_exploration_planner";
01560         marker.id = 100;
01561         marker.type = visualization_msgs::Marker::ARROW;
01562         marker.action = visualization_msgs::Marker::ADD;
01563         marker.pose.position.x = wfx;
01564         marker.pose.position.y = wfy;
01565         marker.pose.position.z = 0.0;
01566         marker.pose.orientation = tf::createQuaternionMsgFromYaw(yaw_path);
01567         marker.scale.x = 0.2;
01568         marker.scale.y = 0.2;
01569         marker.scale.z = 0.2;
01570         marker.color.a = 1.0;
01571         marker.color.r = 0.0;
01572         marker.color.g = 0.0;
01573         marker.color.b = 1.0;
01574         marker.lifetime = ros::Duration(5,0);
01575         visualization_pub_.publish(marker);
01576       }
01577       return true;
01578     }
01579   }
01580   return false;
01581 }
01582 
01583 /*
01584  * checks if a given point is a frontier cell. a frontier cell is a cell in the occupancy grid
01585  * that seperates known from unknown space. Therefore the cell has to be free but at least three
01586  * of its neighbours need to be unknown
01587  */
01588 bool HectorExplorationPlanner::isFrontier(int point){
01589   if(isFreeFrontiers(point)){
01590 
01591     int adjacentPoints[8];
01592     getAdjacentPoints(point,adjacentPoints);
01593 
01594     for(int i = 0; i < 8; ++i){
01595       if(isValid(adjacentPoints[i])){
01596         if(occupancy_grid_array_[adjacentPoints[i]] == costmap_2d::NO_INFORMATION){
01597 
01598           int no_inf_count = 0;
01599           int noInfPoints[8];
01600           getAdjacentPoints(adjacentPoints[i],noInfPoints);
01601           for(int j = 0; j < 8; j++){
01602 
01603 
01604             if( isValid(noInfPoints[j]) && occupancy_grid_array_[noInfPoints[j]] == costmap_2d::NO_INFORMATION){
01605               ++no_inf_count;
01606 
01607               if(no_inf_count > 2){
01608                 return true;
01609               }
01610             }
01611           }
01612         }
01613       }
01614     }
01615   }
01616 
01617   return false;
01618 }
01619 
01620 
01621 void HectorExplorationPlanner::resetMaps(){
01622   std::fill_n(exploration_trans_array_.get(), num_map_cells_, UINT_MAX);
01623   std::fill_n(obstacle_trans_array_.get(), num_map_cells_, UINT_MAX);
01624   std::fill_n(is_goal_array_.get(), num_map_cells_, false);
01625 }
01626 
01627 void HectorExplorationPlanner::clearFrontiers(){
01628   std::fill_n(frontier_map_array_.get(), num_map_cells_, 0);
01629 }
01630 
01631 inline bool HectorExplorationPlanner::isValid(int point){
01632   return (point>=0);
01633 }
01634 
01635 bool HectorExplorationPlanner::isFree(int point){
01636 
01637   if(isValid(point)){
01638     // if a point is not inscribed_inflated_obstacle, leathal_obstacle or no_information, its free
01639 
01640 
01641     if(p_use_inflated_obs_){
01642       if(occupancy_grid_array_[point] < costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
01643         return true;
01644       }
01645     } else {
01646       if(occupancy_grid_array_[point] <= costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
01647         return true;
01648       }
01649     }
01650 
01651     if(p_plan_in_unknown_){
01652       if(occupancy_grid_array_[point] == costmap_2d::NO_INFORMATION){
01653         return true;
01654       }
01655     }
01656   }
01657   return false;
01658 }
01659 
01660 bool HectorExplorationPlanner::isFreeFrontiers(int point){
01661 
01662   if(isValid(point)){
01663     // if a point is not inscribed_inflated_obstacle, leathal_obstacle or no_information, its free
01664 
01665 
01666     if(p_use_inflated_obs_){
01667       if(occupancy_grid_array_[point] < costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
01668         return true;
01669       }
01670     } else {
01671       if(occupancy_grid_array_[point] <= costmap_2d::INSCRIBED_INFLATED_OBSTACLE){
01672         return true;
01673       }
01674     }
01675   }
01676   return false;
01677 }
01678 
01679 bool HectorExplorationPlanner::isFrontierReached(int point){
01680 
01681   tf::Stamped<tf::Pose> robotPose;
01682   if(!costmap_ros_->getRobotPose(robotPose)){
01683     ROS_WARN("[hector_exploration_planner]: Failed to get RobotPose");
01684   }
01685   geometry_msgs::PoseStamped robotPoseMsg;
01686   tf::poseStampedTFToMsg(robotPose, robotPoseMsg);
01687 
01688   unsigned int fx,fy;
01689   double wfx,wfy;
01690   costmap_->indexToCells(point,fx,fy);
01691   costmap_->mapToWorld(fx,fy,wfx,wfy);
01692 
01693 
01694   double dx = robotPoseMsg.pose.position.x - wfx;
01695   double dy = robotPoseMsg.pose.position.y - wfy;
01696 
01697   if ( (dx*dx) + (dy*dy) < (p_dist_for_goal_reached_*p_dist_for_goal_reached_)) {
01698     ROS_DEBUG("[hector_exploration_planner]: frontier is within the squared range of: %f", p_dist_for_goal_reached_);
01699     return true;
01700   }
01701   return false;
01702 
01703 }
01704 
01705 bool HectorExplorationPlanner::isSameFrontier(int frontier_point1, int frontier_point2){
01706   unsigned int fx1,fy1;
01707   unsigned int fx2,fy2;
01708   double wfx1,wfy1;
01709   double wfx2,wfy2;
01710   costmap_->indexToCells(frontier_point1,fx1,fy1);
01711   costmap_->indexToCells(frontier_point2,fx2,fy2);
01712   costmap_->mapToWorld(fx1,fy1,wfx1,wfy1);
01713   costmap_->mapToWorld(fx2,fy2,wfx2,wfy2);
01714 
01715   double dx = wfx1 - wfx2;
01716   double dy = wfy1 - wfy2;
01717 
01718   if((dx*dx) + (dy*dy) < (p_same_frontier_dist_*p_same_frontier_dist_)){
01719     return true;
01720   }
01721   return false;
01722 }
01723 
01724 inline unsigned int HectorExplorationPlanner::cellDanger(int point){
01725 
01726   if ((int)obstacle_trans_array_[point] <= p_min_obstacle_dist_){
01727     return static_cast<unsigned int>(p_alpha_ * std::pow(p_min_obstacle_dist_ - obstacle_trans_array_[point], 2) + .5);
01728   }
01729   //ROS_INFO("%d", (int)obstacle_trans_array_[point] );
01730   //return 80000u - std::min(80000u, obstacle_trans_array_[point]*40);
01731 
01732   //return (2000u - std::min(2000u, obstacle_trans_array_[point])) / 500u;
01733   //std::cout << obstacle_trans_array_[point] << "\n";
01734 
01735   return 0;
01736 }
01737 
01738 float HectorExplorationPlanner::angleDifference(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal){
01739   // setup start positions
01740   unsigned int mxs,mys;
01741   costmap_->worldToMap(start.pose.position.x,start.pose.position.y,mxs,mys);
01742 
01743   unsigned int gx,gy;
01744   costmap_->worldToMap(goal.pose.position.x,goal.pose.position.y,gx,gy);
01745 
01746   int goal_proj_x = gx-mxs;
01747   int goal_proj_y = gy-mys;
01748 
01749   float start_angle = tf::getYaw(start.pose.orientation);
01750   float goal_angle = std::atan2(goal_proj_y,goal_proj_x);
01751 
01752   float both_angle = 0;
01753   if(start_angle > goal_angle){
01754     both_angle = start_angle - goal_angle;
01755   } else {
01756     both_angle = goal_angle - start_angle;
01757   }
01758 
01759   if(both_angle > M_PI){
01760     both_angle = (M_PI - std::abs(start_angle)) + (M_PI - std::abs(goal_angle));
01761   }
01762 
01763   return both_angle;
01764 }
01765 
01766 // Used to generate direction for frontiers
01767 double HectorExplorationPlanner::getYawToUnknown(int point){
01768   int adjacentPoints[8];
01769   getAdjacentPoints(point,adjacentPoints);
01770 
01771   int max_obs_idx = 0;
01772   unsigned int max_obs_dist = 0;
01773 
01774   for(int i = 0; i < 8; ++i){
01775     if(isValid(adjacentPoints[i])){
01776       if(occupancy_grid_array_[adjacentPoints[i]] == costmap_2d::NO_INFORMATION){
01777         if(obstacle_trans_array_[adjacentPoints[i]] > max_obs_dist){
01778           max_obs_idx = i;
01779           max_obs_dist = obstacle_trans_array_[adjacentPoints[i]];
01780         }
01781       }
01782     }
01783   }
01784 
01785   int orientationPoint = adjacentPoints[max_obs_idx];
01786   unsigned int sx,sy,gx,gy;
01787   costmap_->indexToCells((unsigned int)point,sx,sy);
01788   costmap_->indexToCells((unsigned int)orientationPoint,gx,gy);
01789   int x = gx-sx;
01790   int y = gy-sy;
01791   double yaw = std::atan2(y,x);
01792 
01793   return yaw;
01794 
01795 }
01796 
01797 unsigned int HectorExplorationPlanner::angleDanger(float angle){
01798   float angle_fraction = std::pow(angle,3);
01799   unsigned int result = static_cast<unsigned int>(p_goal_angle_penalty_ * angle_fraction);
01800   return result;
01801 }
01802 
01803 float HectorExplorationPlanner::getDistanceWeight(const geometry_msgs::PoseStamped &point1, const geometry_msgs::PoseStamped &point2){
01804   float distance = std::sqrt(std::pow(point1.pose.position.x - point2.pose.position.x,2) + std::pow(point1.pose.position.y - point2.pose.position.y,2));
01805   if(distance < 0.5){
01806     return 5.0;
01807   } else {
01808     return 1;
01809   }
01810 }
01811 
01812 /*
01813  These functions calculate the index of an adjacent point (left,upleft,up,upright,right,downright,down,downleft) to the
01814  given point. If there is no such point (meaning the point would cause the index to be out of bounds), -1 is returned.
01815  */
01816 inline void HectorExplorationPlanner::getStraightPoints(int point, int points[]){
01817 
01818   points[0] = left(point);
01819   points[1] = up(point);
01820   points[2] = right(point);
01821   points[3] = down(point);
01822 
01823 }
01824 
01825 inline void HectorExplorationPlanner::getDiagonalPoints(int point, int points[]){
01826 
01827   points[0] = upleft(point);
01828   points[1] = upright(point);
01829   points[2] = downright(point);
01830   points[3] = downleft(point);
01831 
01832 }
01833 
01834 /*
01835 inline void HectorExplorationPlanner::getStraightAndDiagonalPoints(int point, int straight_points[], int diag_points[]){
01836   /
01837   // Can go up if index is larger than width
01838   bool up = (point >= (int)map_width_);
01839 
01840   // Can go down if
01841   bool down = ((point/map_width_) < (map_width_-1));
01842 
01843 
01844   bool right = ((point + 1) % map_width_ != 0);
01845   bool left = ((point % map_width_ != 0));
01846 
01847 }
01848 */
01849 
01850 inline void HectorExplorationPlanner::getAdjacentPoints(int point, int points[]){
01851 
01852   points[0] = left(point);
01853   points[1] = up(point);
01854   points[2] = right(point);
01855   points[3] = down(point);
01856   points[4] = upleft(point);
01857   points[5] = upright(point);
01858   points[6] = downright(point);
01859   points[7] = downleft(point);
01860 
01861 }
01862 
01863 inline int HectorExplorationPlanner::left(int point){
01864   // only go left if no index error and if current point is not already on the left boundary
01865   if((point % map_width_ != 0)){
01866     return point-1;
01867   }
01868   return -1;
01869 }
01870 inline int HectorExplorationPlanner::upleft(int point){
01871   if((point % map_width_ != 0) && (point >= (int)map_width_)){
01872     return point-1-map_width_;
01873   }
01874   return -1;
01875 
01876 }
01877 inline int HectorExplorationPlanner::up(int point){
01878   if(point >= (int)map_width_){
01879     return point-map_width_;
01880   }
01881   return -1;
01882 }
01883 inline int HectorExplorationPlanner::upright(int point){
01884   if((point >= (int)map_width_) && ((point + 1) % (int)map_width_ != 0)){
01885     return point-map_width_+1;
01886   }
01887   return -1;
01888 }
01889 inline int HectorExplorationPlanner::right(int point){
01890   if((point + 1) % map_width_ != 0){
01891     return point+1;
01892   }
01893   return -1;
01894 
01895 }
01896 inline int HectorExplorationPlanner::downright(int point){
01897   if(((point + 1) % map_width_ != 0) && ((point/map_width_) < (map_height_-1))){
01898     return point+map_width_+1;
01899   }
01900   return -1;
01901 
01902 }
01903 inline int HectorExplorationPlanner::down(int point){
01904   if((point/map_width_) < (map_height_-1)){
01905     return point+map_width_;
01906   }
01907   return -1;
01908 
01909 }
01910 inline int HectorExplorationPlanner::downleft(int point){
01911   if(((point/map_width_) < (map_height_-1)) && (point % map_width_ != 0)){
01912     return point+map_width_-1;
01913   }
01914   return -1;
01915 
01916 }
01917 
01918 //        // visualization (export to another method?)
01919 //        visualization_msgs::Marker marker;
01920 //        marker.header.frame_id = "map";
01921 //        marker.header.stamp = ros::Time();
01922 //        marker.ns = "hector_exploration_planner";
01923 //        marker.id = i + 500;
01924 //        marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
01925 //        marker.action = visualization_msgs::Marker::ADD;
01926 //        marker.pose.position = goals[i].pose.position;
01927 //        marker.scale.x = 0.2;
01928 //        marker.scale.y = 0.2;
01929 //        marker.scale.z = 0.2;
01930 //        marker.color.a = 1.0;
01931 //        marker.color.r = 0.0;
01932 //        marker.color.g = 0.0;
01933 //        marker.color.b = 1.0;
01934 //        marker.lifetime = ros::Duration(5,0);
01935 //        marker.text = boost::lexical_cast<std::string>((int)init_cost) + " - " + boost::lexical_cast<std::string>(getDistanceWeight(start,goals[i]));
01936 //        visualization_pub_.publish(marker);
01937 
01938 //void HectorExplorationPlanner::saveMaps(std::string path){
01939 
01940 //    char costmapPath[1000];
01941 //    sprintf(costmapPath,"%s.map",path.data());
01942 //    char explorationPath[1000];
01943 //    sprintf(explorationPath,"%s.expl",path.data());
01944 //    char obstaclePath[1000];
01945 //    sprintf(obstaclePath,"%s.obs",path.data());
01946 //    char frontierPath[1000];
01947 //    sprintf(frontierPath,"%s.front",path.data());
01948 
01949 
01950 //    costmap.saveMap(costmapPath);
01951 //    FILE *fp_expl = fopen(explorationPath,"w");
01952 //    FILE *fp_obs = fopen(obstaclePath,"w");
01953 //    FILE *fp_front = fopen(frontierPath,"w");
01954 
01955 //    if (!fp_expl || !fp_obs || !fp_front)
01956 //    {
01957 //        ROS_WARN("[hector_exploration_planner] Cannot save maps");
01958 //        return;
01959 //    }
01960 
01961 //    for(unsigned int y = 0; y < map_height_; ++y){
01962 //        for(unsigned int x = 0;x < map_width_; ++x){
01963 //            unsigned int expl = exploration_trans_array_[costmap.getIndex(x,y)];
01964 //            unsigned int obs = obstacle_trans_array_[costmap.getIndex(x,y)];
01965 //            int blobVal = frontier_map_array_[costmap.getIndex(x,y)];
01966 //            fprintf(fp_front,"%d\t", blobVal);
01967 //            fprintf(fp_expl,"%d\t", expl);
01968 //            fprintf(fp_obs, "%d\t", obs);
01969 //        }
01970 //        fprintf(fp_expl,"\n");
01971 //        fprintf(fp_obs,"\n");
01972 //        fprintf(fp_front,"\n");
01973 //    }
01974 
01975 //    fclose(fp_expl);
01976 //    fclose(fp_obs);
01977 //    fclose(fp_front);
01978 //    ROS_INFO("[hector_exploration_planner] Maps have been saved!");
01979 //    return;
01980 
01981 //}
01982 
01983 //    // add last point to path (goal point)
01984 //    for(unsigned int i = 0; i < goals.size(); ++i){
01985 //        unsigned int mx,my;
01986 //        costmap.worldToMap(goals[i].pose.position.x,goals[i].pose.position.y,mx,my);
01987 
01988 //        if(currentPoint == (int)costmap.getIndex(mx,my)){
01989 //            plan.push_back(goals[i]);
01990 //            previous_goal_ = currentPoint;
01991 //        }
01992 
01993 //    }
01994 


hector_exploration_planner
Author(s):
autogenerated on Wed May 8 2019 02:32:10