hector_exploration_planner.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012, Mark Sollweck, Stefan Kohlbrecher, Florian Berz TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
30 
31 #include <visualization_msgs/Marker.h>
32 #include <visualization_msgs/MarkerArray.h>
33 #include <hector_nav_msgs/GetRobotTrajectory.h>
34 #include <Eigen/Geometry>
35 
36 #include <hector_exploration_planner/ExplorationPlannerConfig.h>
37 
38 #define STRAIGHT_COST 100
39 #define DIAGONAL_COST 141
40 
41 //#define STRAIGHT_COST 3
42 //#define DIAGONAL_COST 4
43 
44 using namespace hector_exploration_planner;
45 
47 : costmap_ros_(0)
48 , costmap_(0)
49 , initialized_(false)
50 , map_width_(0)
51 , map_height_(0)
52 , num_map_cells_(0)
53 {}
54 
56  this->deleteMapData();
57 }
58 
60 costmap_ros_(NULL), initialized_(false) {
61  HectorExplorationPlanner::initialize(name, costmap_ros_in);
62 }
63 
65 
67  // unknown: 255, obstacle 254, inflated: 253, free: 0
68 
69  if(initialized_){
70  ROS_ERROR("[hector_exploration_planner] HectorExplorationPlanner is already initialized_! Please check why initialize() got called twice.");
71  return;
72  }
73 
74  ROS_INFO("[hector_exploration_planner] Initializing HectorExplorationPlanner");
75 
76  // initialize costmaps
77  this->costmap_ros_ = costmap_ros_in;
78  this->setupMapData();
79 
80  // initialize parameters
81  ros::NodeHandle private_nh_("~/" + name);
82  ros::NodeHandle nh;
83  visualization_pub_ = private_nh_.advertise<visualization_msgs::Marker>("visualization_marker", 1);
84 
85  observation_pose_pub_ = private_nh_.advertise<geometry_msgs::PoseStamped>("observation_pose", 1, true);
86  goal_pose_pub_ = private_nh_.advertise<geometry_msgs::PoseStamped>("goal_pose", 1, true);
87 
88  dyn_rec_server_.reset(new dynamic_reconfigure::Server<hector_exploration_planner::ExplorationPlannerConfig>(ros::NodeHandle("~/hector_exploration_planner")));
89 
90  dyn_rec_server_->setCallback(boost::bind(&HectorExplorationPlanner::dynRecParamCallback, this, _1, _2));
91 
92  path_service_client_ = nh.serviceClient<hector_nav_msgs::GetRobotTrajectory>("trajectory");
93 
94  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_);
95  //p_min_obstacle_dist_ = p_min_obstacle_dist_ * STRAIGHT_COST;
96 
97  this->name = name;
98  this->initialized_ = true;
99  this->previous_goal_ = -1;
100 
101  vis_.reset(new ExplorationTransformVis("exploration_transform"));
102  close_path_vis_.reset(new ExplorationTransformVis("close_path_exploration_transform"));
103  inner_vis_.reset(new ExplorationTransformVis("inner_exploration_transform"));
104  obstacle_vis_.reset(new ExplorationTransformVis("obstacle_transform"));
105 }
106 
107 void HectorExplorationPlanner::dynRecParamCallback(hector_exploration_planner::ExplorationPlannerConfig &config, uint32_t level)
108 {
109  p_plan_in_unknown_ = config.plan_in_unknown;
110  p_explore_close_to_path_ = config.explore_close_to_path;
111  p_use_inflated_obs_ = config.use_inflated_obstacles;
112  p_goal_angle_penalty_ = config.goal_angle_penalty;
113  p_alpha_ = config.security_constant;
114  p_dist_for_goal_reached_ = config.dist_for_goal_reached;
115  p_same_frontier_dist_ = config.same_frontier_distance;
116  p_min_frontier_size_ = config.min_frontier_size;
117  p_min_obstacle_dist_ = config.min_obstacle_dist * STRAIGHT_COST;
118  p_obstacle_cutoff_dist_ = config.obstacle_cutoff_distance;
119 
120  p_use_observation_pose_calculation_ = config.use_observation_pose_calculation;
121  p_observation_pose_desired_dist_ = config.observation_pose_desired_dist;
122  double angle_rad = config.observation_pose_allowed_angle * (M_PI / 180.0);
124  p_close_to_path_target_distance_ = config.close_to_path_target_distance;
125 }
126 
127 bool HectorExplorationPlanner::makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &original_goal, std::vector<geometry_msgs::PoseStamped> &plan){
128 
129  this->setupMapData();
130 
131  // do exploration? (not used anymore? -> call doExploration())
132 
133  if ((original_goal.pose.orientation.w == 0.0) && (original_goal.pose.orientation.x == 0.0) &&
134  (original_goal.pose.orientation.y == 0.0) && (original_goal.pose.orientation.z == 0.0)){
135  ROS_ERROR("Trying to plan with invalid quaternion, this shouldn't be done anymore, but we'll start exploration for now.");
136  return doExploration(start,plan);
137  }
138 
139 
140  // planning
141  ROS_INFO("[hector_exploration_planner] planning: starting to make a plan to given goal point");
142 
143  // setup maps and goals
144  resetMaps();
145  plan.clear();
146 
147  std::vector<geometry_msgs::PoseStamped> goals;
148 
149  // create obstacle tranform
150  //buildobstacle_trans_array_(p_use_inflated_obs_);
151 
152  goal_pose_pub_.publish(original_goal);
153 
154  geometry_msgs::PoseStamped adjusted_goal;
155 
157  ROS_INFO("Using observation pose calc.");
158  if (!this->getObservationPose(original_goal, p_observation_pose_desired_dist_, adjusted_goal)){
159  ROS_ERROR("getObservationPose returned false, no area around target point available to drive to!");
160  return false;
161  }
162  }else{
163  ROS_INFO("Not using observation pose calc.");
164  this->buildobstacle_trans_array_(true);
165  adjusted_goal = original_goal;
166  }
167 
168  observation_pose_pub_.publish(adjusted_goal);
169 
170  // plan to given goal
171  goals.push_back(adjusted_goal);
172 
173  // make plan
174  if(!buildexploration_trans_array_(start,goals,true)){
175  return false;
176  }
177  if(!getTrajectory(start,goals,plan)){
178  return false;
179  }
180 
181  // save and add last point
182  plan.push_back(adjusted_goal);
183  unsigned int mx,my;
184  costmap_->worldToMap(adjusted_goal.pose.position.x,adjusted_goal.pose.position.y,mx,my);
185  previous_goal_ = costmap_->getIndex(mx,my);
186 
187  if ((original_goal.pose.orientation.w == 0.0) && (original_goal.pose.orientation.x == 0.0) &&
188  (original_goal.pose.orientation.y == 0.0) && (original_goal.pose.orientation.z == 0.0)){
189  geometry_msgs::PoseStamped second_last_pose;
190  geometry_msgs::PoseStamped last_pose;
191  second_last_pose = plan[plan.size()-2];
192  last_pose = plan[plan.size()-1];
193  last_pose.pose.orientation = second_last_pose.pose.orientation;
194  plan[plan.size()-1] = last_pose;
195 
196 
197  }
198 
199  ROS_INFO("[hector_exploration_planner] planning: plan has been found! plansize: %u ", (unsigned int)plan.size());
200  return true;
201 }
202 
203 bool HectorExplorationPlanner::doExploration(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &plan){
204 
205 
206 
207  this->setupMapData();
208 
209  // setup maps and goals
210 
211  resetMaps();
212  clearFrontiers();
213  plan.clear();
214 
215  std::vector<geometry_msgs::PoseStamped> goals;
216 
217  // create obstacle tranform
219 
220 
221  bool frontiers_found = false;
222 
224 
225  frontiers_found = findFrontiersCloseToPath(goals);
226 
227  if (!frontiers_found){
228  ROS_WARN("Close Exploration desired, but no frontiers found. Falling back to normal exploration!");
229  frontiers_found = findFrontiers(goals);
230  }
231 
232  }else{
233  frontiers_found = findFrontiers(goals);
234  }
235 
236  // search for frontiers
237  if(frontiers_found){
238 
240  ROS_INFO("[hector_exploration_planner] exploration: found %u frontiers!", (unsigned int)goals.size());
241  } else {
242  ROS_INFO("[hector_exploration_planner] exploration: no frontiers have been found! starting inner-exploration");
243  return doInnerExploration(start,plan);
244  }
245 
246  // make plan
247  if(!buildexploration_trans_array_(start,goals,true)){
248  return false;
249  }
250 
251  if(!getTrajectory(start,goals,plan)){
252  ROS_INFO("[hector_exploration_planner] exploration: could not plan to frontier, starting inner-exploration");
253  return doInnerExploration(start,plan);
254  }
255 
256  // update previous goal
257  if(!plan.empty()){
258  geometry_msgs::PoseStamped thisgoal = plan.back();
259  unsigned int mx,my;
260  costmap_->worldToMap(thisgoal.pose.position.x,thisgoal.pose.position.y,mx,my);
261  previous_goal_ = costmap_->getIndex(mx,my);
262  }
263 
264 
265  ROS_INFO("[hector_exploration_planner] exploration: plan to a frontier has been found! plansize: %u", (unsigned int)plan.size());
266  return true;
267 }
268 
269 bool HectorExplorationPlanner::doInnerExploration(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &plan){
270  ROS_INFO("[hector_exploration_planner] inner-exploration: starting exploration");
271 
272  // setup maps and goals
273 
274  resetMaps();
275  clearFrontiers();
276  plan.clear();
277 
278  std::vector<geometry_msgs::PoseStamped> goals;
279 
280  // create obstacle tranform
282 
283  // If we have been in inner explore before, check if we have reached the previous inner explore goal
284  if (last_mode_ == INNER_EXPLORE){
285 
286  tf::Stamped<tf::Pose> robotPose;
287  if(!costmap_ros_->getRobotPose(robotPose)){
288  ROS_WARN("[hector_exploration_planner]: Failed to get RobotPose");
289  }
290 
291  unsigned int xm, ym;
293 
294  double xw, yw;
295  costmap_->mapToWorld(xm, ym, xw, yw);
296 
297  double dx = xw - robotPose.getOrigin().getX();
298  double dy = yw - robotPose.getOrigin().getY();
299 
300  //If we have not reached the previous goal, try planning and moving toward it.
301  //If planning fails, we just continue below this block and try to find another inner frontier
302  if ( (dx*dx + dy*dy) > 0.5*0.5){
303 
304  geometry_msgs::PoseStamped robotPoseMsg;
305  tf::poseStampedTFToMsg(robotPose, robotPoseMsg);
306 
307  geometry_msgs::PoseStamped goalMsg;
308  goalMsg.pose.position.x = xw;
309  goalMsg.pose.position.y = yw;
310  goalMsg.pose.orientation.w = 1.0;
311 
312  if(makePlan(robotPoseMsg, goalMsg, plan)){
313  //Successfully generated plan to (previous) inner explore goal
314  ROS_INFO("[hector_exploration_planner] inner-exploration: Planning to previous inner frontier");
316  return true;
317  }
318  }
319  }
320 
321  // search for frontiers
322  if(findInnerFrontier(goals)){
323  ROS_INFO("[hector_exploration_planner] inner-exploration: found %u inner-frontiers!", (unsigned int)goals.size());
324  } else {
325  ROS_WARN("[hector_exploration_planner] inner-exploration: no inner-frontiers have been found! exploration failed!");
326  return false;
327  }
328 
329  // make plan
330  if(!buildexploration_trans_array_(start,goals,false)){
331  ROS_WARN("[hector_exploration_planner] inner-exploration: Creating exploration transform failed!");
332  return false;
333  }
334  if(!getTrajectory(start,goals,plan)){
335  ROS_WARN("[hector_exploration_planner] inner-exploration: could not plan to inner-frontier. exploration failed!");
336  return false;
337  }
338 
339  // cutoff last points of plan due to sbpl error when planning close to walls
340 
341  int plansize = plan.size() - 5;
342  if(plansize > 0 ){
343  plan.resize(plansize);
344  }
345 
346  // update previous goal
347  if(!plan.empty()){
348  const geometry_msgs::PoseStamped& thisgoal = plan.back();
349  unsigned int mx,my;
350  costmap_->worldToMap(thisgoal.pose.position.x,thisgoal.pose.position.y,mx,my);
351  previous_goal_ = costmap_->getIndex(mx,my);
353  }
354 
355  ROS_INFO("[hector_exploration_planner] inner-exploration: plan to an inner-frontier has been found! plansize: %u", (unsigned int)plan.size());
356  return true;
357 }
358 
359 bool HectorExplorationPlanner::getObservationPose(const geometry_msgs::PoseStamped& observation_pose, const double desired_distance, geometry_msgs::PoseStamped& new_observation_pose)
360 {
361  // We call this from inside the planner, so map data setup and reset already happened
362  //this->setupMapData();
363  //resetMaps();
364 
366  ROS_WARN("getObservationPose was called although use_observation_pose_calculation param is set to false. Returning original pose!");
367  new_observation_pose = observation_pose;
368  this->buildobstacle_trans_array_(true);
369  return true;
370  }
371 
372  unsigned int mxs,mys;
373  costmap_->worldToMap(observation_pose.pose.position.x, observation_pose.pose.position.y, mxs, mys);
374 
375  double pose_yaw = tf::getYaw(observation_pose.pose.orientation);
376 
377  Eigen::Vector2f obs_pose_dir_vec (cos(pose_yaw), sin(pose_yaw));
378 
379  this->buildobstacle_trans_array_(true);
380 
381  int searchSize = 2.0 / costmap_->getResolution();
382 
383  int min_x = mxs - searchSize/2;
384  int min_y = mys - searchSize/2;
385 
386  if (min_x < 0){
387  min_x = 0;
388  }
389 
390  if (min_y < 0){
391  min_y = 0;
392  }
393 
394  int max_x = mxs + searchSize/2;
395  int max_y = mys + searchSize/2;
396 
397  if (max_x > static_cast<int>(costmap_->getSizeInCellsX())){
398  max_x = static_cast<int>(costmap_->getSizeInCellsX()-1);
399  }
400 
401  if (max_y > static_cast<int>(costmap_->getSizeInCellsY())){
402  max_y = static_cast<int>(costmap_->getSizeInCellsY()-1);
403  }
404 
405  int closest_x = -1;
406  int closest_y = -1;
407 
408  unsigned int closest_sqr_dist = UINT_MAX;
409 
410  bool no_information = true;
411 
412  for (int x = min_x; x < max_x; ++x){
413  for (int y = min_y; y < max_y; ++y){
414 
415  unsigned int point = costmap_->getIndex(x,y);
416 
417  unsigned int obstacle_trans_val = obstacle_trans_array_[point];
418 
419  if ( (obstacle_trans_val != UINT_MAX) && (obstacle_trans_val != 0) && (occupancy_grid_array_[point] != costmap_2d::NO_INFORMATION)){
420 
421  no_information = false;
422 
423  int diff_x = x - (int)mxs;
424  int diff_y = y - (int)mys;
425 
426  unsigned int sqr_dist = diff_x*diff_x + diff_y*diff_y;
427 
428  //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";
429 
430  if (sqr_dist < closest_sqr_dist){
431 
432  Eigen::Vector2f curr_dir_vec(static_cast<float>(diff_x), static_cast<float>(diff_y));
433  curr_dir_vec.normalize();
434 
435  if (curr_dir_vec.dot(obs_pose_dir_vec) < p_cos_of_allowed_observation_pose_angle_){
436 
437  closest_x = (unsigned int)x;
438  closest_y = (unsigned int)y;
439  closest_sqr_dist = sqr_dist;
440  }
441  }
442  }
443  }
444  }
445 
446  if (no_information){
447  new_observation_pose.pose = observation_pose.pose;
448  new_observation_pose.pose.position.z = 0.0;
449  ROS_INFO("Observation pose unchanged as no information available around goal area");
450  return true;
451  }
452 
453  //std::cout << "start: " << mxs << " , " << mys << " min: " << min_x << " , " << min_y << " max: " << max_x << " , " << max_y << "\n";
454  //std::cout << "pos: " << closest_x << " , " << closest_y << "\n";
455 
456  // Found valid pose if both coords are larger than -1
457  if ((closest_x > -1) && (closest_y > -1)){
458 
459  Eigen::Vector2d closest_point_world;
460  costmap_->mapToWorld(closest_x, closest_y, closest_point_world.x(), closest_point_world.y());
461 
462  Eigen::Vector2d original_goal_pose(observation_pose.pose.position.x, observation_pose.pose.position.y);
463 
464  //geometry_msgs::PoseStamped pose;
465  new_observation_pose.header.frame_id = "map";
466  new_observation_pose.header.stamp = observation_pose.header.stamp;
467 
468  Eigen::Vector2d dir_vec(original_goal_pose - closest_point_world);
469 
470  double distance = dir_vec.norm();
471 
472  //If we get back the original observation pose (or another one very close to it), return that
473  if (distance < (costmap_->getResolution() * 1.5)){
474  new_observation_pose.pose = observation_pose.pose;
475  new_observation_pose.pose.position.z = 0.0;
476  ROS_INFO("Observation pose unchanged");
477  }else{
478 
479  if (desired_distance < distance){
480  new_observation_pose.pose.position.x = closest_point_world.x();
481  new_observation_pose.pose.position.y = closest_point_world.y();
482  new_observation_pose.pose.position.z = 0.0;
483  }else{
484 
485  double test_distance = distance;
486 
487  Eigen::Vector2d last_valid_pos(closest_point_world);
488 
489  do{
490  test_distance += 0.1;
491 
492  double distance_factor = test_distance / distance;
493 
494  Eigen::Vector2d new_pos(original_goal_pose - dir_vec*distance_factor);
495 
496  unsigned int x, y;
497  costmap_->worldToMap(new_pos[0], new_pos[1], x, y);
498  unsigned int idx = costmap_->getIndex(x,y);
499 
500  if(!this->isFree(idx)){
501  break;
502  }
503 
504  last_valid_pos = new_pos;
505 
506  }while (test_distance < desired_distance);
507 
508  new_observation_pose.pose.position.x = last_valid_pos.x();
509  new_observation_pose.pose.position.y = last_valid_pos.y();
510  new_observation_pose.pose.position.z = 0.0;
511  }
512 
513  double angle = std::atan2(dir_vec.y(), dir_vec.x());
514 
515  new_observation_pose.pose.orientation.w = cos(angle*0.5);
516  new_observation_pose.pose.orientation.x = 0.0;
517  new_observation_pose.pose.orientation.y = 0.0;
518  new_observation_pose.pose.orientation.z = sin(angle*0.5);
519  ROS_INFO("Observation pose moved away from wall");
520  }
521 
522  return true;
523  }else{
524  // If closest vals are still -1, we didn't find a position
525  ROS_ERROR("Couldn't find observation pose for given point.");
526  return false;
527  }
528 }
529 
530 bool HectorExplorationPlanner::doAlternativeExploration(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &plan, std::vector<geometry_msgs::PoseStamped> &oldplan){
531  ROS_INFO("[hector_exploration_planner] alternative exploration: starting alternative exploration");
532 
533  // setup maps and goals
534  resetMaps();
535  plan.clear();
536 
537  std::vector<geometry_msgs::PoseStamped> goals;
538 
539  std::vector<geometry_msgs::PoseStamped> old_frontier;
540  old_frontier.push_back(oldplan.back());
541 
542  // create obstacle tranform
544 
545  // search for frontiers
546  if(findFrontiers(goals,old_frontier)){
547  ROS_INFO("[hector_exploration_planner] alternative exploration: found %u frontiers!", (unsigned int) goals.size());
548  } else {
549  ROS_WARN("[hector_exploration_planner] alternative exploration: no frontiers have been found!");
550  return false;
551  }
552 
553  // make plan
554  if(!buildexploration_trans_array_(start,goals,true)){
555  return false;
556  }
557  if(!getTrajectory(start,goals,plan)){
558  return false;
559  }
560 
561  const geometry_msgs::PoseStamped& this_goal = plan.back();
562  unsigned int mx,my;
563  costmap_->worldToMap(this_goal.pose.position.x,this_goal.pose.position.y,mx,my);
564  previous_goal_ = costmap_->getIndex(mx,my);
565 
566  ROS_INFO("[hector_exploration_planner] alternative exploration: plan to a frontier has been found! plansize: %u ", (unsigned int)plan.size());
567  return true;
568 }
569 
570 float HectorExplorationPlanner::angleDifferenceWall(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal){
571  // setup start positions
572  unsigned int mxs,mys;
573  costmap_->worldToMap(start.pose.position.x,start.pose.position.y,mxs,mys);
574 
575  unsigned int gx,gy;
576  costmap_->worldToMap(goal.pose.position.x,goal.pose.position.y,gx,gy);
577 
578  int goal_proj_x = gx-mxs;
579  int goal_proj_y = gy-mys;
580 
581  float start_angle = tf::getYaw(start.pose.orientation);
582  float goal_angle = std::atan2(goal_proj_y,goal_proj_x);
583 
584  float both_angle = 0;
585  if(start_angle > goal_angle){
586  both_angle = start_angle - goal_angle;
587  } else {
588  both_angle = goal_angle - start_angle;
589  }
590 
591  return both_angle;
592 }
593 
594 bool HectorExplorationPlanner::exploreWalls(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> &plan){
595 
596  //@TODO: Properly set this parameters
597  int startExploreWall = 1;
598 
599  ROS_DEBUG("[hector_exploration_planner] wall-follow: exploreWalls");
600  unsigned int mx,my;
601  if(!costmap_->worldToMap(start.pose.position.x, start.pose.position.y, mx, my)){
602  ROS_WARN("[hector_exploration_planner] wall-follow: The start coordinates are outside the costmap!");
603  return false;
604  }
605  int currentPoint=costmap_->getIndex(mx, my);
606  int nextPoint;
607  int oldDirection = -1;
608  int k=0;
609  int loop=0;
610 
611  while(k<50){
612  int adjacentPoints [8];
613  getAdjacentPoints(currentPoint, adjacentPoints);
614  int dirPoints [3];
615 
616  unsigned int minDelta = UINT_MAX;
617  unsigned int maxDelta = 0;
618  unsigned int thisDelta;
619  float minAngle=3.1415; //Rad -> 180°
620 
621  geometry_msgs::PoseStamped trajPoint;
622  unsigned int gx,gy;
623 
624  if(oldDirection==-1){
625  // find robot orientation
626  for ( int i=0; i<8; i++){
627  costmap_->indexToCells((unsigned int)adjacentPoints[i],gx,gy);
628  double wx,wy;
629  costmap_->mapToWorld(gx,gy,wx,wy);
630  std::string global_frame = costmap_ros_->getGlobalFrameID();
631  trajPoint.header.frame_id = global_frame;
632  trajPoint.pose.position.x = wx;
633  trajPoint.pose.position.y = wy;
634  trajPoint.pose.position.z = 0.0;
635  float yaw = angleDifferenceWall(start, trajPoint);
636  if(yaw < minAngle){
637  minAngle=yaw;
638  oldDirection=i;
639  }
640  }
641  }
642 
643  //search possible orientation
644 
645  if (oldDirection == 0){
646  dirPoints[0]=oldDirection+4; //right-forward
647  dirPoints[1]=oldDirection; //forward
648  dirPoints[2]=oldDirection+7; //left-forward
649  }
650  else if (oldDirection < 3){
651  dirPoints[0]=oldDirection+4;
652  dirPoints[1]=oldDirection;
653  dirPoints[2]=oldDirection+3;
654  }
655  else if (oldDirection == 3){
656  dirPoints[0]=oldDirection+4;
657  dirPoints[1]=oldDirection;
658  dirPoints[2]=oldDirection+3;
659  }
660  else if (oldDirection == 4){
661  dirPoints[0]=oldDirection-3;
662  dirPoints[1]=oldDirection;
663  dirPoints[2]=oldDirection-4;
664  }
665  else if (oldDirection < 7){
666  dirPoints[0]=oldDirection-3;
667  dirPoints[1]=oldDirection;
668  dirPoints[2]=oldDirection-4;
669  }
670  else if (oldDirection == 7){
671  dirPoints[0]=oldDirection-7;
672  dirPoints[1]=oldDirection;
673  dirPoints[2]=oldDirection-4;
674  }
675 
676  // decide LHR or RHR
677  if(startExploreWall == -1){
678  if(obstacle_trans_array_[adjacentPoints[dirPoints[0]]] <= obstacle_trans_array_[adjacentPoints[dirPoints[2]]]){
679  startExploreWall = 0;
680  ROS_INFO("[hector_exploration_planner] wall-follow: RHR");//mirror inverted??
681  }
682  else {
683  startExploreWall = 1;
684  ROS_INFO("[hector_exploration_planner] wall-follow: LHR");//mirror inverted??
685  }
686  }
687 
688 
689 
690  //switch left and right, LHR
691  if(startExploreWall == 1){
692  int temp=dirPoints[0];
693  dirPoints[0]=dirPoints[2];
694  dirPoints[2]=temp;
695  }
696 
697 
698  // find next point
699  int t=0;
700  for(int i=0; i<3; i++){
701  thisDelta = obstacle_trans_array_[adjacentPoints[dirPoints[i]]];
702 
703  if (thisDelta > 3000 || loop > 7) // point is unknown or robot drive loop
704  {
705  int plansize = plan.size() - 4;
706  if(plansize > 0 ){
707  plan.resize(plansize);
708  }
709  ROS_DEBUG("[hector_exploration_planner] wall-follow: END: exploreWalls. Plansize %d", (int)plan.size());
710  return !plan.empty();
711  }
712 
713  if(thisDelta >= (unsigned int) p_min_obstacle_dist_){
714  if(obstacle_trans_array_[currentPoint] >= (unsigned int) p_min_obstacle_dist_){
715  if(abs(thisDelta - p_min_obstacle_dist_) < minDelta){
716  minDelta = abs(thisDelta - p_min_obstacle_dist_);
717  nextPoint = adjacentPoints[dirPoints[i]];
718  oldDirection = dirPoints[i];
719  }
720  }
721  if(obstacle_trans_array_[currentPoint] < (unsigned int) p_min_obstacle_dist_){
722  if(thisDelta > maxDelta){
723  maxDelta = thisDelta;
724  nextPoint = adjacentPoints[dirPoints[i]];
725  oldDirection = dirPoints[i];
726  }
727  }
728  }
729  else {
730  if(thisDelta < obstacle_trans_array_[currentPoint]){
731  t++;
732  }
733  if(thisDelta > maxDelta){
734  maxDelta = thisDelta;
735  nextPoint = adjacentPoints[dirPoints[i]];
736  oldDirection = dirPoints[i];
737 
738  }
739  }
740  }
741 
742  if(t==3 && abs(obstacle_trans_array_[adjacentPoints[dirPoints[0]]] - obstacle_trans_array_[adjacentPoints[dirPoints[1]]]) < STRAIGHT_COST
743  && abs(obstacle_trans_array_[adjacentPoints[dirPoints[0]]] - obstacle_trans_array_[adjacentPoints[dirPoints[2]]]) < STRAIGHT_COST
744  && abs(obstacle_trans_array_[adjacentPoints[dirPoints[1]]] - obstacle_trans_array_[adjacentPoints[dirPoints[2]]]) < STRAIGHT_COST){
745  nextPoint=adjacentPoints[dirPoints[2]];
746  oldDirection=dirPoints[2];
747  }
748 
749  if(oldDirection==dirPoints[2])
750  loop++;
751  else
752  loop=0;
753 
754  // add point
755  unsigned int sx,sy;
756  costmap_->indexToCells((unsigned int)currentPoint,sx,sy);
757  costmap_->indexToCells((unsigned int)nextPoint,gx,gy);
758  double wx,wy;
759  costmap_->mapToWorld(sx,sy,wx,wy);
760  std::string global_frame = costmap_ros_->getGlobalFrameID();
761  trajPoint.header.frame_id = global_frame;
762  trajPoint.pose.position.x = wx;
763  trajPoint.pose.position.y = wy;
764  trajPoint.pose.position.z = 0.0;
765  // assign orientation
766  int dx = gx-sx;
767  int dy = gy-sy;
768  double yaw_path = std::atan2(dy,dx);
769  trajPoint.pose.orientation.x = 0.0;
770  trajPoint.pose.orientation.y = 0.0;
771  trajPoint.pose.orientation.z = sin(yaw_path*0.5f);
772  trajPoint.pose.orientation.w = cos(yaw_path*0.5f);
773  plan.push_back(trajPoint);
774 
775  currentPoint=nextPoint;
776  k++;
777  }
778  ROS_DEBUG("[hector_exploration_planner] wall-follow: END: exploreWalls. Plansize %d", (int)plan.size());
779  return !plan.empty();
780 }
781 
783 {
784 
785 #ifdef COSTMAP_2D_LAYERED_COSTMAP_H_
787 #else
788  if (costmap_) delete costmap_;
790  costmap_ros_->getCostmapCopy(*costmap_);
791 #endif
792 
793  //Below code can be used to guarantee start pose is cleared. Somewhat risky.
794  //@TODO: Make available through dynamic reconfigure
795  /*
796  std::vector<geometry_msgs::Point> points;
797  costmap_ros_->getOrientedFootprint(points);
798 
799  bool filled = costmap_->setConvexPolygonCost(points, costmap_2d::FREE_SPACE);
800 
801  //std::vector<geometry_msgs::Point> points = costmap_ros_->getRobotFootprint();
802  for (size_t i = 0; i < points.size(); ++i)
803  std::cout << points[i];
804  if (filled)
805  ROS_INFO("Set costmap to free");
806  else
807  ROS_INFO("Failed to set costmap free");
808  */
809 
810  if ((this->map_width_ != costmap_->getSizeInCellsX()) || (this->map_height_ != costmap_->getSizeInCellsY())){
814 
815  // initialize exploration_trans_array_, obstacle_trans_array_, goalMap and frontier_map_array_
816  exploration_trans_array_.reset(new unsigned int[num_map_cells_]);
817  obstacle_trans_array_.reset(new unsigned int[num_map_cells_]);
818  is_goal_array_.reset(new bool[num_map_cells_]);
819  frontier_map_array_.reset(new int[num_map_cells_]);
820  clearFrontiers();
821  resetMaps();
822  }
823 
825 }
826 
828 {
829  exploration_trans_array_.reset();
830  obstacle_trans_array_.reset();
831  is_goal_array_.reset();
832  frontier_map_array_.reset();
833 }
834 
835 
836 bool HectorExplorationPlanner::buildexploration_trans_array_(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> goals, bool useAnglePenalty, bool use_cell_danger){
837 
838  ROS_DEBUG("[hector_exploration_planner] buildexploration_trans_array_");
839 
840  // reset exploration transform
841  std::fill_n(exploration_trans_array_.get(), num_map_cells_, UINT_MAX);
842  std::fill_n(is_goal_array_.get(), num_map_cells_, false);
843 
844  std::queue<int> myqueue;
845 
846  size_t num_free_goals = 0;
847 
848  // initialize goals
849  for(unsigned int i = 0; i < goals.size(); ++i){
850  // setup goal positions
851  unsigned int mx,my;
852 
853  if(!costmap_->worldToMap(goals[i].pose.position.x,goals[i].pose.position.y,mx,my)){
854  //ROS_WARN("[hector_exploration_planner] The goal coordinates are outside the costmap!");
855  continue;
856  }
857 
858  int goal_point = costmap_->getIndex(mx,my);
859 
860  // Ignore free goal for the moment, check after iterating over all goals if there is not valid one at all
861  if(!isFree(goal_point)){
862  continue;
863  }else{
864  ++num_free_goals;
865  }
866 
867  unsigned int init_cost = 0;
868  if(false){
869  init_cost = angleDanger(angleDifference(start,goals[i])) * getDistanceWeight(start,goals[i]);
870  }
871 
872  exploration_trans_array_[goal_point] = init_cost;
873 
874  // do not punish previous frontiers (oscillation)
875  if(false && isValid(previous_goal_)){
876  if(isSameFrontier(goal_point, previous_goal_)){
877  ROS_DEBUG("[hector_exploration_planner] same frontier: init with 0");
878  exploration_trans_array_[goal_point] = 0;
879  }
880  }
881 
882  ROS_DEBUG("[hector_exploration_planner] Goal init cost: %d, point: %d", exploration_trans_array_[goal_point], goal_point);
883  is_goal_array_[goal_point] = true;
884  myqueue.push(goal_point);
885  }
886 
887  if (num_free_goals == 0){
888  ROS_WARN("[hector_exploration_planner] All goal coordinates for exploration transform invalid (occupied or out of bounds), aborting.");
889  return false;
890  }
891 
892  // exploration transform algorithm
893  if (use_cell_danger){
894  while(myqueue.size()){
895  int point = myqueue.front();
896  myqueue.pop();
897 
898  unsigned int minimum = exploration_trans_array_[point];
899 
900  int straightPoints[4];
901  getStraightPoints(point,straightPoints);
902  int diagonalPoints[4];
903  getDiagonalPoints(point,diagonalPoints);
904 
905  // calculate the minimum exploration value of all adjacent cells
906  for (int i = 0; i < 4; ++i) {
907  if (isFree(straightPoints[i])) {
908  unsigned int neighbor_cost = minimum + STRAIGHT_COST + cellDanger(straightPoints[i]);
909 
910  if (exploration_trans_array_[straightPoints[i]] > neighbor_cost) {
911  exploration_trans_array_[straightPoints[i]] = neighbor_cost;
912  myqueue.push(straightPoints[i]);
913  }
914  }
915 
916  if (isFree(diagonalPoints[i])) {
917  unsigned int neighbor_cost = minimum + DIAGONAL_COST + cellDanger(diagonalPoints[i]);
918 
919  if (exploration_trans_array_[diagonalPoints[i]] > neighbor_cost) {
920  exploration_trans_array_[diagonalPoints[i]] = neighbor_cost;
921  myqueue.push(diagonalPoints[i]);
922  }
923  }
924  }
925  }
926  }else{
927  while(myqueue.size()){
928  int point = myqueue.front();
929  myqueue.pop();
930 
931  unsigned int minimum = exploration_trans_array_[point];
932 
933  int straightPoints[4];
934  getStraightPoints(point,straightPoints);
935  int diagonalPoints[4];
936  getDiagonalPoints(point,diagonalPoints);
937 
938  // calculate the minimum exploration value of all adjacent cells
939  for (int i = 0; i < 4; ++i) {
940  if (isFree(straightPoints[i])) {
941  unsigned int neighbor_cost = minimum + STRAIGHT_COST;
942 
943  if (exploration_trans_array_[straightPoints[i]] > neighbor_cost) {
944  exploration_trans_array_[straightPoints[i]] = neighbor_cost;
945  myqueue.push(straightPoints[i]);
946  }
947  }
948 
949  if (isFree(diagonalPoints[i])) {
950  unsigned int neighbor_cost = minimum + DIAGONAL_COST;
951 
952  if (exploration_trans_array_[diagonalPoints[i]] > neighbor_cost) {
953  exploration_trans_array_[diagonalPoints[i]] = neighbor_cost;
954  myqueue.push(diagonalPoints[i]);
955  }
956  }
957  }
958  }
959  }
960 
961  ROS_DEBUG("[hector_exploration_planner] END: buildexploration_trans_array_");
962 
963  vis_->publishVisOnDemand(*costmap_, exploration_trans_array_.get());
964  return true;
965 }
966 
968  ROS_DEBUG("[hector_exploration_planner] buildobstacle_trans_array_");
969  std::queue<int> myqueue;
970 
971  // init obstacles
972  for(unsigned int i=0; i < num_map_cells_; ++i){
974  myqueue.push(i);
975  obstacle_trans_array_[i] = 0;
976  } else if(use_inflated_obstacles){
978  myqueue.push(i);
979  obstacle_trans_array_[i] = 0;
980  }
981  }
982  }
983 
984  unsigned int obstacle_cutoff_value = static_cast<unsigned int>((p_obstacle_cutoff_dist_ / costmap_->getResolution()) * STRAIGHT_COST + 0.5);
985 
986  // obstacle transform algorithm
987  while(myqueue.size()){
988  int point = myqueue.front();
989  myqueue.pop();
990 
991  unsigned int minimum = obstacle_trans_array_[point];
992  if (minimum > obstacle_cutoff_value) continue;
993 
994  int straightPoints[4];
995  getStraightPoints(point,straightPoints);
996  int diagonalPoints[4];
997  getDiagonalPoints(point,diagonalPoints);
998 
999  // check all 8 directions
1000  for(int i = 0; i < 4; ++i){
1001  if (isValid(straightPoints[i]) && (obstacle_trans_array_[straightPoints[i]] > minimum + STRAIGHT_COST)) {
1002  obstacle_trans_array_[straightPoints[i]] = minimum + STRAIGHT_COST;
1003  myqueue.push(straightPoints[i]);
1004  }
1005  if (isValid(diagonalPoints[i]) && (obstacle_trans_array_[diagonalPoints[i]] > minimum + DIAGONAL_COST)) {
1006  obstacle_trans_array_[diagonalPoints[i]] = minimum + DIAGONAL_COST;
1007  myqueue.push(diagonalPoints[i]);
1008  }
1009  }
1010  }
1011 
1012  ROS_DEBUG("[hector_exploration_planner] END: buildobstacle_trans_array_");
1013 
1014  obstacle_vis_->publishVisOnDemand(*costmap_, obstacle_trans_array_.get());
1015  return true;
1016 }
1017 
1018 bool HectorExplorationPlanner::getTrajectory(const geometry_msgs::PoseStamped &start, std::vector<geometry_msgs::PoseStamped> goals, std::vector<geometry_msgs::PoseStamped> &plan){
1019 
1020  ROS_DEBUG("[hector_exploration_planner] getTrajectory");
1021 
1022  // setup start positions
1023  unsigned int mx,my;
1024 
1025  if(!costmap_->worldToMap(start.pose.position.x,start.pose.position.y,mx,my)){
1026  ROS_WARN("[hector_exploration_planner] The start coordinates are outside the costmap!");
1027  return false;
1028  }
1029 
1030  int currentPoint = costmap_->getIndex(mx,my);
1031  int nextPoint = currentPoint;
1032 
1033 
1034 
1035  geometry_msgs::PoseStamped trajPoint;
1036  std::string global_frame = costmap_ros_->getGlobalFrameID();
1037  trajPoint.header.frame_id = global_frame;
1038 
1039  if (is_goal_array_[currentPoint]){
1040  ROS_INFO("Already at goal point position. No pose vector generated.");
1041  return true;
1042  }
1043 
1044  while(!is_goal_array_[currentPoint]){
1045  int thisDelta;
1046  int adjacentPoints[8];
1047  getAdjacentPoints(currentPoint,adjacentPoints);
1048 
1049  int maxDelta = 0;
1050 
1051  for(int i = 0; i < 8; ++i){
1052  if(isFree(adjacentPoints[i])){
1053  thisDelta = exploration_trans_array_[currentPoint] - exploration_trans_array_[adjacentPoints[i]];
1054  if(thisDelta > maxDelta){
1055  maxDelta = thisDelta;
1056  nextPoint = adjacentPoints[i];
1057  }
1058  }
1059  }
1060 
1061  // This happens when there is no valid exploration transform data at the start point for example
1062  if(maxDelta == 0){
1063  ROS_WARN("[hector_exploration_planner] No path to the goal could be found by following gradient!");
1064  return false;
1065  }
1066 
1067 
1068  // make trajectory point
1069  unsigned int sx,sy,gx,gy;
1070  costmap_->indexToCells((unsigned int)currentPoint,sx,sy);
1071  costmap_->indexToCells((unsigned int)nextPoint,gx,gy);
1072  double wx,wy;
1073  costmap_->mapToWorld(sx,sy,wx,wy);
1074 
1075  trajPoint.pose.position.x = wx;
1076  trajPoint.pose.position.y = wy;
1077  trajPoint.pose.position.z = 0.0;
1078 
1079  // assign orientation
1080  int dx = gx-sx;
1081  int dy = gy-sy;
1082  double yaw_path = std::atan2(dy,dx);
1083  trajPoint.pose.orientation.x = 0.0;
1084  trajPoint.pose.orientation.y = 0.0;
1085  trajPoint.pose.orientation.z = sin(yaw_path*0.5f);
1086  trajPoint.pose.orientation.w = cos(yaw_path*0.5f);
1087 
1088  plan.push_back(trajPoint);
1089 
1090  currentPoint = nextPoint;
1091  maxDelta = 0;
1092  }
1093 
1094  ROS_DEBUG("[hector_exploration_planner] END: getTrajectory. Plansize %u", (unsigned int)plan.size());
1095  return !plan.empty();
1096 }
1097 
1098 bool HectorExplorationPlanner::findFrontiers(std::vector<geometry_msgs::PoseStamped> &frontiers){
1099  std::vector<geometry_msgs::PoseStamped> empty_vec;
1100  return findFrontiers(frontiers,empty_vec);
1101 }
1102 
1103 /*
1104  * searches the occupancy grid for frontier cells and merges them into one target point per frontier.
1105  * The returned frontiers are in world coordinates.
1106  */
1107 bool HectorExplorationPlanner::findFrontiersCloseToPath(std::vector<geometry_msgs::PoseStamped> &frontiers){
1108 
1109  clearFrontiers();
1110  frontiers.clear();
1111 
1112  // get the trajectory as seeds for the exploration transform
1113  hector_nav_msgs::GetRobotTrajectory srv_path;
1114  if (path_service_client_.call(srv_path)){
1115 
1116  std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
1117 
1118  // We push poses of the travelled trajectory to the goals vector for building the exploration transform
1119  std::vector<geometry_msgs::PoseStamped> goals;
1120 
1121  size_t size = traj_vector.size();
1122  ROS_INFO("[hector_exploration_planner] Size of trajectory vector for close exploration %u", (unsigned int)size);
1123 
1124  if(size > 0){
1125  geometry_msgs::PoseStamped lastPose = traj_vector[size-1];
1126  goals.push_back(lastPose);
1127 
1128  if (size > 1){
1129 
1130  for(int i = static_cast<int>(size-2); i >= 0; --i){
1131  const geometry_msgs::PoseStamped& pose = traj_vector[i];
1132  unsigned int x,y;
1133  costmap_->worldToMap(pose.pose.position.x,pose.pose.position.y,x,y);
1134  unsigned int m_point = costmap_->getIndex(x,y);
1135 
1136  double dx = lastPose.pose.position.x - pose.pose.position.x;
1137  double dy = lastPose.pose.position.y - pose.pose.position.y;
1138 
1139  if((dx*dx) + (dy*dy) > (0.25*0.25)){
1140  goals.push_back(pose);
1141  lastPose = pose;
1142  }
1143  }
1144 
1145  ROS_INFO("[hector_exploration_planner] pushed %u goals (trajectory) for close to robot frontier search", (unsigned int)goals.size());
1146 
1147  // make exploration transform
1148  tf::Stamped<tf::Pose> robotPose;
1149  if(!costmap_ros_->getRobotPose(robotPose)){
1150  ROS_WARN("[hector_exploration_planner]: Failed to get RobotPose");
1151  }
1152  geometry_msgs::PoseStamped robotPoseMsg;
1153  tf::poseStampedTFToMsg(robotPose, robotPoseMsg);
1154 
1155  if (!buildexploration_trans_array_(robotPoseMsg, goals, false, false)){
1156  ROS_WARN("[hector_exploration_planner]: Creating exploration transform array in find inner frontier failed, aborting.");
1157  return false;
1158  }
1159 
1160  close_path_vis_->publishVisOnDemand(*costmap_, exploration_trans_array_.get());
1161 
1162  unsigned int explore_threshold = static_cast<unsigned int> (static_cast<double>(STRAIGHT_COST) * (1.0/costmap_->getResolution()) * p_close_to_path_target_distance_);
1163 
1164  //std::vector<geometry_msgs::PoseStamped> close_frontiers;
1165 
1166  for(unsigned int i = 0; i < num_map_cells_; ++i){
1167 
1168  unsigned int current_val = exploration_trans_array_[i];
1169 
1170  if(current_val < UINT_MAX){
1171 
1172  if (current_val >= explore_threshold){ //&& current_val <= explore_threshold+ DIAGONAL_COST){
1173  geometry_msgs::PoseStamped finalFrontier;
1174  double wx,wy;
1175  unsigned int mx,my;
1176  costmap_->indexToCells(i, mx, my);
1177  costmap_->mapToWorld(mx,my,wx,wy);
1178  std::string global_frame = costmap_ros_->getGlobalFrameID();
1179  finalFrontier.header.frame_id = global_frame;
1180  finalFrontier.pose.position.x = wx;
1181  finalFrontier.pose.position.y = wy;
1182  finalFrontier.pose.position.z = 0.0;
1183 
1184  double yaw = getYawToUnknown(costmap_->getIndex(mx,my));
1185 
1186  //if(frontier_is_valid){
1187 
1188  finalFrontier.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
1189 
1190  frontiers.push_back(finalFrontier);
1191 
1192  }
1193 
1194  }
1195  }
1196 
1197  return frontiers.size() > 0;
1198 
1199 
1200 
1201 
1202 
1203  }
1204  }
1205  }
1206 
1207 
1208 
1209 
1210 
1211  // list of all frontiers in the occupancy grid
1212  std::vector<int> allFrontiers;
1213 
1214  // check for all cells in the occupancy grid whether or not they are frontier cells
1215  for(unsigned int i = 0; i < num_map_cells_; ++i){
1216  if(isFrontier(i)){
1217  allFrontiers.push_back(i);
1218  }
1219  }
1220 
1221  for(unsigned int i = 0; i < allFrontiers.size(); ++i){
1222  if(!isFrontierReached(allFrontiers[i])){
1223  geometry_msgs::PoseStamped finalFrontier;
1224  double wx,wy;
1225  unsigned int mx,my;
1226  costmap_->indexToCells(allFrontiers[i], mx, my);
1227  costmap_->mapToWorld(mx,my,wx,wy);
1228  std::string global_frame = costmap_ros_->getGlobalFrameID();
1229  finalFrontier.header.frame_id = global_frame;
1230  finalFrontier.pose.position.x = wx;
1231  finalFrontier.pose.position.y = wy;
1232  finalFrontier.pose.position.z = 0.0;
1233 
1234  double yaw = getYawToUnknown(costmap_->getIndex(mx,my));
1235 
1236  //if(frontier_is_valid){
1237 
1238  finalFrontier.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
1239 
1240  frontiers.push_back(finalFrontier);
1241  }
1242  //}
1243  }
1244 
1245  return (frontiers.size() > 0);
1246 }
1247 
1248 /*
1249  * searches the occupancy grid for frontier cells and merges them into one target point per frontier.
1250  * The returned frontiers are in world coordinates.
1251  */
1252 bool HectorExplorationPlanner::findFrontiers(std::vector<geometry_msgs::PoseStamped> &frontiers, std::vector<geometry_msgs::PoseStamped> &noFrontiers){
1253 
1254  // get latest costmap
1255  clearFrontiers();
1256 
1257  // list of all frontiers in the occupancy grid
1258  std::vector<int> allFrontiers;
1259 
1260  // check for all cells in the occupancy grid whether or not they are frontier cells
1261  for(unsigned int i = 0; i < num_map_cells_; ++i){
1262  if(isFrontier(i)){
1263  allFrontiers.push_back(i);
1264  }
1265  }
1266 
1267  for(unsigned int i = 0; i < allFrontiers.size(); ++i){
1268  if(!isFrontierReached(allFrontiers[i])){
1269  geometry_msgs::PoseStamped finalFrontier;
1270  double wx,wy;
1271  unsigned int mx,my;
1272  costmap_->indexToCells(allFrontiers[i], mx, my);
1273  costmap_->mapToWorld(mx,my,wx,wy);
1274  std::string global_frame = costmap_ros_->getGlobalFrameID();
1275  finalFrontier.header.frame_id = global_frame;
1276  finalFrontier.pose.position.x = wx;
1277  finalFrontier.pose.position.y = wy;
1278  finalFrontier.pose.position.z = 0.0;
1279 
1280  double yaw = getYawToUnknown(costmap_->getIndex(mx,my));
1281 
1282  //if(frontier_is_valid){
1283 
1284  finalFrontier.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
1285 
1286  frontiers.push_back(finalFrontier);
1287  }
1288  //}
1289  }
1290 
1291  return (frontiers.size() > 0);
1292 
1293  //@TODO: Review and possibly remove unused code below
1294 
1295  // value of the next blob
1296  int nextBlobValue = 1;
1297  std::list<int> usedBlobs;
1298 
1299  for(unsigned int i = 0; i < allFrontiers.size(); ++i){
1300 
1301  // get all adjacent blobs to the current frontier point
1302  int currentPoint = allFrontiers[i];
1303  int adjacentPoints[8];
1304  getAdjacentPoints(currentPoint,adjacentPoints);
1305 
1306  std::list<int> blobs;
1307 
1308  for(int j = 0; j < 8; j++){
1309  if(isValid(adjacentPoints[j]) && (frontier_map_array_[adjacentPoints[j]] > 0)){
1310  blobs.push_back(frontier_map_array_[adjacentPoints[j]]);
1311  }
1312  }
1313  blobs.unique();
1314 
1315  if(blobs.empty()){
1316  // create new blob
1317  frontier_map_array_[currentPoint] = nextBlobValue;
1318  usedBlobs.push_back(nextBlobValue);
1319  nextBlobValue++;
1320  } else {
1321  // merge all found blobs
1322  int blobMergeVal = 0;
1323 
1324  for(std::list<int>::iterator adjBlob = blobs.begin(); adjBlob != blobs.end(); ++adjBlob){
1325  if(adjBlob == blobs.begin()){
1326  blobMergeVal = *adjBlob;
1327  frontier_map_array_[currentPoint] = blobMergeVal;
1328  } else {
1329 
1330  for(unsigned int k = 0; k < allFrontiers.size(); k++){
1331  if(frontier_map_array_[allFrontiers[k]] == *adjBlob){
1332  usedBlobs.remove(*adjBlob);
1333  frontier_map_array_[allFrontiers[k]] = blobMergeVal;
1334  }
1335  }
1336  }
1337  }
1338  }
1339  }
1340 
1341  int id = 1;
1342 
1343  bool visualization_requested = (visualization_pub_.getNumSubscribers() > 0);
1344 
1345  // summarize every blob into a single point (maximum obstacle_trans_array_ value)
1346  for(std::list<int>::iterator currentBlob = usedBlobs.begin(); currentBlob != usedBlobs.end(); ++currentBlob){
1347  int current_frontier_size = 0;
1348  int max_obs_idx = 0;
1349 
1350  for(unsigned int i = 0; i < allFrontiers.size(); ++i){
1351  int point = allFrontiers[i];
1352 
1353  if(frontier_map_array_[point] == *currentBlob){
1354  current_frontier_size++;
1355  if(obstacle_trans_array_[point] > obstacle_trans_array_[allFrontiers[max_obs_idx]]){
1356  max_obs_idx = i;
1357  }
1358  }
1359  }
1360 
1361  if(current_frontier_size < p_min_frontier_size_){
1362  continue;
1363  }
1364 
1365  int frontier_point = allFrontiers[max_obs_idx];
1366  unsigned int x,y;
1367  costmap_->indexToCells(frontier_point,x,y);
1368 
1369  // check if frontier is valid (not to close to robot and not in noFrontiers vector
1370  bool frontier_is_valid = true;
1371 
1372  if(isFrontierReached(frontier_point)){
1373  frontier_is_valid = false;
1374  }
1375 
1376  for(size_t i = 0; i < noFrontiers.size(); ++i){
1377  const geometry_msgs::PoseStamped& noFrontier = noFrontiers[i];
1378  unsigned int mx,my;
1379  costmap_->worldToMap(noFrontier.pose.position.x,noFrontier.pose.position.y,mx,my);
1380  int no_frontier_point = costmap_->getIndex(x,y);
1381  if(isSameFrontier(frontier_point,no_frontier_point)){
1382  frontier_is_valid = false;
1383  }
1384  }
1385 
1386  geometry_msgs::PoseStamped finalFrontier;
1387  double wx,wy;
1388  costmap_->mapToWorld(x,y,wx,wy);
1389  std::string global_frame = costmap_ros_->getGlobalFrameID();
1390  finalFrontier.header.frame_id = global_frame;
1391  finalFrontier.pose.position.x = wx;
1392  finalFrontier.pose.position.y = wy;
1393  finalFrontier.pose.position.z = 0.0;
1394 
1395  double yaw = getYawToUnknown(costmap_->getIndex(x,y));
1396 
1397  if(frontier_is_valid){
1398 
1399  finalFrontier.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
1400  frontiers.push_back(finalFrontier);
1401  }
1402 
1403  // visualization (export to method?)
1404  if(visualization_requested){
1405  visualization_msgs::Marker marker;
1406  marker.header.frame_id = "map";
1407  marker.header.stamp = ros::Time();
1408  marker.ns = "hector_exploration_planner";
1409  marker.id = id++;
1410  marker.type = visualization_msgs::Marker::ARROW;
1411  marker.action = visualization_msgs::Marker::ADD;
1412  marker.pose.position.x = wx;
1413  marker.pose.position.y = wy;
1414  marker.pose.position.z = 0.0;
1415  marker.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
1416  marker.scale.x = 0.2;
1417  marker.scale.y = 0.2;
1418  marker.scale.z = 0.2;
1419  marker.color.a = 1.0;
1420 
1421  if(frontier_is_valid){
1422  marker.color.r = 0.0;
1423  marker.color.g = 1.0;
1424  }else{
1425  marker.color.r = 1.0;
1426  marker.color.g = 0.0;
1427  }
1428 
1429  marker.color.b = 0.0;
1430  marker.lifetime = ros::Duration(5,0);
1431  visualization_pub_.publish(marker);
1432  }
1433 
1434  }
1435  return !frontiers.empty();
1436 }
1437 
1438 bool HectorExplorationPlanner::findInnerFrontier(std::vector<geometry_msgs::PoseStamped> &innerFrontier){
1439  clearFrontiers();
1440 
1441  // get the trajectory as seeds for the exploration transform
1442  hector_nav_msgs::GetRobotTrajectory srv_path;
1443  if (path_service_client_.call(srv_path)){
1444 
1445  std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
1446 
1447  // We push poses of the travelled trajectory to the goals vector for building the exploration transform
1448  std::vector<geometry_msgs::PoseStamped> goals;
1449 
1450  size_t size = traj_vector.size();
1451  ROS_DEBUG("[hector_exploration_planner] size of trajectory vector %u", (unsigned int)size);
1452 
1453  if(size > 0){
1454  geometry_msgs::PoseStamped lastPose = traj_vector[size-1];
1455  goals.push_back(lastPose);
1456 
1457  if (size > 1){
1458 
1459  // Allow collision at start in case vehicle is (very) close to wall
1460  bool collision_allowed = true;
1461 
1462  for(int i = static_cast<int>(size-2); i >= 0; --i){
1463  const geometry_msgs::PoseStamped& pose = traj_vector[i];
1464  unsigned int x,y;
1465  costmap_->worldToMap(pose.pose.position.x,pose.pose.position.y,x,y);
1466  unsigned int m_point = costmap_->getIndex(x,y);
1467 
1468  double dx = lastPose.pose.position.x - pose.pose.position.x;
1469  double dy = lastPose.pose.position.y - pose.pose.position.y;
1470 
1471  bool point_in_free_space = isFreeFrontiers(m_point);
1472 
1473  // extract points with 0.5m distance (if free)
1474  if(point_in_free_space){
1475  if((dx*dx) + (dy*dy) > (0.25*0.25)){
1476  goals.push_back(pose);
1477  lastPose = pose;
1478  collision_allowed = false;
1479  }
1480  }
1481 
1482  if (!point_in_free_space && !collision_allowed){
1483  break;
1484  }
1485  }
1486  }
1487 
1488 
1489  ROS_DEBUG("[hector_exploration_planner] pushed %u goals (trajectory) for inner frontier-search", (unsigned int)goals.size());
1490 
1491  // make exploration transform
1492  tf::Stamped<tf::Pose> robotPose;
1493  if(!costmap_ros_->getRobotPose(robotPose)){
1494  ROS_WARN("[hector_exploration_planner]: Failed to get RobotPose");
1495  }
1496  geometry_msgs::PoseStamped robotPoseMsg;
1497  tf::poseStampedTFToMsg(robotPose, robotPoseMsg);
1498 
1499  if (!buildexploration_trans_array_(robotPoseMsg, goals, false)){
1500  ROS_WARN("[hector_exploration_planner]: Creating exploration transform array in find inner frontier failed, aborting.");
1501  return false;
1502  }
1503 
1504  inner_vis_->publishVisOnDemand(*costmap_, exploration_trans_array_.get());
1505 
1506  unsigned int x,y;
1507  costmap_->worldToMap(robotPoseMsg.pose.position.x,robotPoseMsg.pose.position.y,x,y);
1508 
1509 
1510 
1511 
1512  // get point with maximal distance to trajectory
1513  int max_exploration_trans_point = -1;
1514  unsigned int max_exploration_trans_val = 0;
1515 
1516  for(unsigned int i = 0; i < num_map_cells_; ++i){
1517 
1518  if(exploration_trans_array_[i] < UINT_MAX){
1519  if(exploration_trans_array_[i] > max_exploration_trans_val){
1520  if(!isFrontierReached(i)){
1521  max_exploration_trans_point = i;
1522  max_exploration_trans_val = exploration_trans_array_[i];
1523  }
1524  }
1525  }
1526  }
1527 
1528  if (max_exploration_trans_point == 0){
1529  ROS_WARN("[hector_exploration_planner]: Couldn't find max exploration transform point for inner exploration, aborting.");
1530  return false;
1531  }
1532 
1533  geometry_msgs::PoseStamped finalFrontier;
1534  unsigned int fx,fy;
1535  double wfx,wfy;
1536  costmap_->indexToCells(max_exploration_trans_point,fx,fy);
1537  costmap_->mapToWorld(fx,fy,wfx,wfy);
1538  std::string global_frame = costmap_ros_->getGlobalFrameID();
1539  finalFrontier.header.frame_id = global_frame;
1540  finalFrontier.pose.position.x = wfx;
1541  finalFrontier.pose.position.y = wfy;
1542  finalFrontier.pose.position.z = 0.0;
1543 
1544  // assign orientation
1545  int dx = fx-x;
1546  int dy = fy-y;
1547  double yaw_path = std::atan2(dy,dx);
1548  finalFrontier.pose.orientation.x = 0.0;
1549  finalFrontier.pose.orientation.y = 0.0;
1550  finalFrontier.pose.orientation.z = sin(yaw_path*0.5f);
1551  finalFrontier.pose.orientation.w = cos(yaw_path*0.5f);
1552 
1553  innerFrontier.push_back(finalFrontier);
1554 
1556  visualization_msgs::Marker marker;
1557  marker.header.frame_id = "map";
1558  marker.header.stamp = ros::Time();
1559  marker.ns = "hector_exploration_planner";
1560  marker.id = 100;
1561  marker.type = visualization_msgs::Marker::ARROW;
1562  marker.action = visualization_msgs::Marker::ADD;
1563  marker.pose.position.x = wfx;
1564  marker.pose.position.y = wfy;
1565  marker.pose.position.z = 0.0;
1566  marker.pose.orientation = tf::createQuaternionMsgFromYaw(yaw_path);
1567  marker.scale.x = 0.2;
1568  marker.scale.y = 0.2;
1569  marker.scale.z = 0.2;
1570  marker.color.a = 1.0;
1571  marker.color.r = 0.0;
1572  marker.color.g = 0.0;
1573  marker.color.b = 1.0;
1574  marker.lifetime = ros::Duration(5,0);
1575  visualization_pub_.publish(marker);
1576  }
1577  return true;
1578  }
1579  }
1580  return false;
1581 }
1582 
1583 /*
1584  * checks if a given point is a frontier cell. a frontier cell is a cell in the occupancy grid
1585  * that seperates known from unknown space. Therefore the cell has to be free but at least three
1586  * of its neighbours need to be unknown
1587  */
1589  if(isFreeFrontiers(point)){
1590 
1591  int adjacentPoints[8];
1592  getAdjacentPoints(point,adjacentPoints);
1593 
1594  for(int i = 0; i < 8; ++i){
1595  if(isValid(adjacentPoints[i])){
1596  if(occupancy_grid_array_[adjacentPoints[i]] == costmap_2d::NO_INFORMATION){
1597 
1598  int no_inf_count = 0;
1599  int noInfPoints[8];
1600  getAdjacentPoints(adjacentPoints[i],noInfPoints);
1601  for(int j = 0; j < 8; j++){
1602 
1603 
1604  if( isValid(noInfPoints[j]) && occupancy_grid_array_[noInfPoints[j]] == costmap_2d::NO_INFORMATION){
1605  ++no_inf_count;
1606 
1607  if(no_inf_count > 2){
1608  return true;
1609  }
1610  }
1611  }
1612  }
1613  }
1614  }
1615  }
1616 
1617  return false;
1618 }
1619 
1620 
1622  std::fill_n(exploration_trans_array_.get(), num_map_cells_, UINT_MAX);
1623  std::fill_n(obstacle_trans_array_.get(), num_map_cells_, UINT_MAX);
1624  std::fill_n(is_goal_array_.get(), num_map_cells_, false);
1625 }
1626 
1628  std::fill_n(frontier_map_array_.get(), num_map_cells_, 0);
1629 }
1630 
1631 inline bool HectorExplorationPlanner::isValid(int point){
1632  return (point>=0);
1633 }
1634 
1636 
1637  if(isValid(point)){
1638  // if a point is not inscribed_inflated_obstacle, leathal_obstacle or no_information, its free
1639 
1640 
1641  if(p_use_inflated_obs_){
1643  return true;
1644  }
1645  } else {
1647  return true;
1648  }
1649  }
1650 
1651  if(p_plan_in_unknown_){
1653  return true;
1654  }
1655  }
1656  }
1657  return false;
1658 }
1659 
1661 
1662  if(isValid(point)){
1663  // if a point is not inscribed_inflated_obstacle, leathal_obstacle or no_information, its free
1664 
1665 
1666  if(p_use_inflated_obs_){
1668  return true;
1669  }
1670  } else {
1672  return true;
1673  }
1674  }
1675  }
1676  return false;
1677 }
1678 
1680 
1681  tf::Stamped<tf::Pose> robotPose;
1682  if(!costmap_ros_->getRobotPose(robotPose)){
1683  ROS_WARN("[hector_exploration_planner]: Failed to get RobotPose");
1684  }
1685  geometry_msgs::PoseStamped robotPoseMsg;
1686  tf::poseStampedTFToMsg(robotPose, robotPoseMsg);
1687 
1688  unsigned int fx,fy;
1689  double wfx,wfy;
1690  costmap_->indexToCells(point,fx,fy);
1691  costmap_->mapToWorld(fx,fy,wfx,wfy);
1692 
1693 
1694  double dx = robotPoseMsg.pose.position.x - wfx;
1695  double dy = robotPoseMsg.pose.position.y - wfy;
1696 
1697  if ( (dx*dx) + (dy*dy) < (p_dist_for_goal_reached_*p_dist_for_goal_reached_)) {
1698  ROS_DEBUG("[hector_exploration_planner]: frontier is within the squared range of: %f", p_dist_for_goal_reached_);
1699  return true;
1700  }
1701  return false;
1702 
1703 }
1704 
1705 bool HectorExplorationPlanner::isSameFrontier(int frontier_point1, int frontier_point2){
1706  unsigned int fx1,fy1;
1707  unsigned int fx2,fy2;
1708  double wfx1,wfy1;
1709  double wfx2,wfy2;
1710  costmap_->indexToCells(frontier_point1,fx1,fy1);
1711  costmap_->indexToCells(frontier_point2,fx2,fy2);
1712  costmap_->mapToWorld(fx1,fy1,wfx1,wfy1);
1713  costmap_->mapToWorld(fx2,fy2,wfx2,wfy2);
1714 
1715  double dx = wfx1 - wfx2;
1716  double dy = wfy1 - wfy2;
1717 
1718  if((dx*dx) + (dy*dy) < (p_same_frontier_dist_*p_same_frontier_dist_)){
1719  return true;
1720  }
1721  return false;
1722 }
1723 
1724 inline unsigned int HectorExplorationPlanner::cellDanger(int point){
1725 
1726  if ((int)obstacle_trans_array_[point] <= p_min_obstacle_dist_){
1727  return static_cast<unsigned int>(p_alpha_ * std::pow(p_min_obstacle_dist_ - obstacle_trans_array_[point], 2) + .5);
1728  }
1729  //ROS_INFO("%d", (int)obstacle_trans_array_[point] );
1730  //return 80000u - std::min(80000u, obstacle_trans_array_[point]*40);
1731 
1732  //return (2000u - std::min(2000u, obstacle_trans_array_[point])) / 500u;
1733  //std::cout << obstacle_trans_array_[point] << "\n";
1734 
1735  return 0;
1736 }
1737 
1738 float HectorExplorationPlanner::angleDifference(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal){
1739  // setup start positions
1740  unsigned int mxs,mys;
1741  costmap_->worldToMap(start.pose.position.x,start.pose.position.y,mxs,mys);
1742 
1743  unsigned int gx,gy;
1744  costmap_->worldToMap(goal.pose.position.x,goal.pose.position.y,gx,gy);
1745 
1746  int goal_proj_x = gx-mxs;
1747  int goal_proj_y = gy-mys;
1748 
1749  float start_angle = tf::getYaw(start.pose.orientation);
1750  float goal_angle = std::atan2(goal_proj_y,goal_proj_x);
1751 
1752  float both_angle = 0;
1753  if(start_angle > goal_angle){
1754  both_angle = start_angle - goal_angle;
1755  } else {
1756  both_angle = goal_angle - start_angle;
1757  }
1758 
1759  if(both_angle > M_PI){
1760  both_angle = (M_PI - std::abs(start_angle)) + (M_PI - std::abs(goal_angle));
1761  }
1762 
1763  return both_angle;
1764 }
1765 
1766 // Used to generate direction for frontiers
1768  int adjacentPoints[8];
1769  getAdjacentPoints(point,adjacentPoints);
1770 
1771  int max_obs_idx = 0;
1772  unsigned int max_obs_dist = 0;
1773 
1774  for(int i = 0; i < 8; ++i){
1775  if(isValid(adjacentPoints[i])){
1776  if(occupancy_grid_array_[adjacentPoints[i]] == costmap_2d::NO_INFORMATION){
1777  if(obstacle_trans_array_[adjacentPoints[i]] > max_obs_dist){
1778  max_obs_idx = i;
1779  max_obs_dist = obstacle_trans_array_[adjacentPoints[i]];
1780  }
1781  }
1782  }
1783  }
1784 
1785  int orientationPoint = adjacentPoints[max_obs_idx];
1786  unsigned int sx,sy,gx,gy;
1787  costmap_->indexToCells((unsigned int)point,sx,sy);
1788  costmap_->indexToCells((unsigned int)orientationPoint,gx,gy);
1789  int x = gx-sx;
1790  int y = gy-sy;
1791  double yaw = std::atan2(y,x);
1792 
1793  return yaw;
1794 
1795 }
1796 
1797 unsigned int HectorExplorationPlanner::angleDanger(float angle){
1798  float angle_fraction = std::pow(angle,3);
1799  unsigned int result = static_cast<unsigned int>(p_goal_angle_penalty_ * angle_fraction);
1800  return result;
1801 }
1802 
1803 float HectorExplorationPlanner::getDistanceWeight(const geometry_msgs::PoseStamped &point1, const geometry_msgs::PoseStamped &point2){
1804  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));
1805  if(distance < 0.5){
1806  return 5.0;
1807  } else {
1808  return 1;
1809  }
1810 }
1811 
1812 /*
1813  These functions calculate the index of an adjacent point (left,upleft,up,upright,right,downright,down,downleft) to the
1814  given point. If there is no such point (meaning the point would cause the index to be out of bounds), -1 is returned.
1815  */
1816 inline void HectorExplorationPlanner::getStraightPoints(int point, int points[]){
1817 
1818  points[0] = left(point);
1819  points[1] = up(point);
1820  points[2] = right(point);
1821  points[3] = down(point);
1822 
1823 }
1824 
1825 inline void HectorExplorationPlanner::getDiagonalPoints(int point, int points[]){
1826 
1827  points[0] = upleft(point);
1828  points[1] = upright(point);
1829  points[2] = downright(point);
1830  points[3] = downleft(point);
1831 
1832 }
1833 
1834 /*
1835 inline void HectorExplorationPlanner::getStraightAndDiagonalPoints(int point, int straight_points[], int diag_points[]){
1836  /
1837  // Can go up if index is larger than width
1838  bool up = (point >= (int)map_width_);
1839 
1840  // Can go down if
1841  bool down = ((point/map_width_) < (map_width_-1));
1842 
1843 
1844  bool right = ((point + 1) % map_width_ != 0);
1845  bool left = ((point % map_width_ != 0));
1846 
1847 }
1848 */
1849 
1850 inline void HectorExplorationPlanner::getAdjacentPoints(int point, int points[]){
1851 
1852  points[0] = left(point);
1853  points[1] = up(point);
1854  points[2] = right(point);
1855  points[3] = down(point);
1856  points[4] = upleft(point);
1857  points[5] = upright(point);
1858  points[6] = downright(point);
1859  points[7] = downleft(point);
1860 
1861 }
1862 
1863 inline int HectorExplorationPlanner::left(int point){
1864  // only go left if no index error and if current point is not already on the left boundary
1865  if((point % map_width_ != 0)){
1866  return point-1;
1867  }
1868  return -1;
1869 }
1870 inline int HectorExplorationPlanner::upleft(int point){
1871  if((point % map_width_ != 0) && (point >= (int)map_width_)){
1872  return point-1-map_width_;
1873  }
1874  return -1;
1875 
1876 }
1877 inline int HectorExplorationPlanner::up(int point){
1878  if(point >= (int)map_width_){
1879  return point-map_width_;
1880  }
1881  return -1;
1882 }
1884  if((point >= (int)map_width_) && ((point + 1) % (int)map_width_ != 0)){
1885  return point-map_width_+1;
1886  }
1887  return -1;
1888 }
1889 inline int HectorExplorationPlanner::right(int point){
1890  if((point + 1) % map_width_ != 0){
1891  return point+1;
1892  }
1893  return -1;
1894 
1895 }
1897  if(((point + 1) % map_width_ != 0) && ((point/map_width_) < (map_height_-1))){
1898  return point+map_width_+1;
1899  }
1900  return -1;
1901 
1902 }
1903 inline int HectorExplorationPlanner::down(int point){
1904  if((point/map_width_) < (map_height_-1)){
1905  return point+map_width_;
1906  }
1907  return -1;
1908 
1909 }
1911  if(((point/map_width_) < (map_height_-1)) && (point % map_width_ != 0)){
1912  return point+map_width_-1;
1913  }
1914  return -1;
1915 
1916 }
1917 
1918 // // visualization (export to another method?)
1919 // visualization_msgs::Marker marker;
1920 // marker.header.frame_id = "map";
1921 // marker.header.stamp = ros::Time();
1922 // marker.ns = "hector_exploration_planner";
1923 // marker.id = i + 500;
1924 // marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
1925 // marker.action = visualization_msgs::Marker::ADD;
1926 // marker.pose.position = goals[i].pose.position;
1927 // marker.scale.x = 0.2;
1928 // marker.scale.y = 0.2;
1929 // marker.scale.z = 0.2;
1930 // marker.color.a = 1.0;
1931 // marker.color.r = 0.0;
1932 // marker.color.g = 0.0;
1933 // marker.color.b = 1.0;
1934 // marker.lifetime = ros::Duration(5,0);
1935 // marker.text = boost::lexical_cast<std::string>((int)init_cost) + " - " + boost::lexical_cast<std::string>(getDistanceWeight(start,goals[i]));
1936 // visualization_pub_.publish(marker);
1937 
1938 //void HectorExplorationPlanner::saveMaps(std::string path){
1939 
1940 // char costmapPath[1000];
1941 // sprintf(costmapPath,"%s.map",path.data());
1942 // char explorationPath[1000];
1943 // sprintf(explorationPath,"%s.expl",path.data());
1944 // char obstaclePath[1000];
1945 // sprintf(obstaclePath,"%s.obs",path.data());
1946 // char frontierPath[1000];
1947 // sprintf(frontierPath,"%s.front",path.data());
1948 
1949 
1950 // costmap.saveMap(costmapPath);
1951 // FILE *fp_expl = fopen(explorationPath,"w");
1952 // FILE *fp_obs = fopen(obstaclePath,"w");
1953 // FILE *fp_front = fopen(frontierPath,"w");
1954 
1955 // if (!fp_expl || !fp_obs || !fp_front)
1956 // {
1957 // ROS_WARN("[hector_exploration_planner] Cannot save maps");
1958 // return;
1959 // }
1960 
1961 // for(unsigned int y = 0; y < map_height_; ++y){
1962 // for(unsigned int x = 0;x < map_width_; ++x){
1963 // unsigned int expl = exploration_trans_array_[costmap.getIndex(x,y)];
1964 // unsigned int obs = obstacle_trans_array_[costmap.getIndex(x,y)];
1965 // int blobVal = frontier_map_array_[costmap.getIndex(x,y)];
1966 // fprintf(fp_front,"%d\t", blobVal);
1967 // fprintf(fp_expl,"%d\t", expl);
1968 // fprintf(fp_obs, "%d\t", obs);
1969 // }
1970 // fprintf(fp_expl,"\n");
1971 // fprintf(fp_obs,"\n");
1972 // fprintf(fp_front,"\n");
1973 // }
1974 
1975 // fclose(fp_expl);
1976 // fclose(fp_obs);
1977 // fclose(fp_front);
1978 // ROS_INFO("[hector_exploration_planner] Maps have been saved!");
1979 // return;
1980 
1981 //}
1982 
1983 // // add last point to path (goal point)
1984 // for(unsigned int i = 0; i < goals.size(); ++i){
1985 // unsigned int mx,my;
1986 // costmap.worldToMap(goals[i].pose.position.x,goals[i].pose.position.y,mx,my);
1987 
1988 // if(currentPoint == (int)costmap.getIndex(mx,my)){
1989 // plan.push_back(goals[i]);
1990 // previous_goal_ = currentPoint;
1991 // }
1992 
1993 // }
1994 
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
boost::shared_ptr< ExplorationTransformVis > close_path_vis_
void publish(const boost::shared_ptr< M > &message) const
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
f
boost::shared_ptr< ExplorationTransformVis > vis_
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
static double getYaw(const Quaternion &bt_q)
bool isSameFrontier(int frontier_point1, int frontier_point2)
std::string getGlobalFrameID()
bool call(MReq &req, MRes &res)
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
unsigned char * getCharMap() const
boost::shared_ptr< ExplorationTransformVis > inner_vis_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
double distance(double x0, double y0, double x1, double y1)
float angleDifferenceWall(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal)
float getDistanceWeight(const geometry_msgs::PoseStamped &point1, const geometry_msgs::PoseStamped &point2)
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
bool getObservationPose(const geometry_msgs::PoseStamped &observation_pose, const double desired_distance, geometry_msgs::PoseStamped &new_observation_pose)
#define ROS_INFO(...)
#define DIAGONAL_COST
bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &original_goal, std::vector< geometry_msgs::PoseStamped > &plan)
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int getSizeInCellsY() const
enum hector_exploration_planner::HectorExplorationPlanner::LastMode last_mode_
#define STRAIGHT_COST
bool findInnerFrontier(std::vector< geometry_msgs::PoseStamped > &innerFrontier)
unsigned int getSizeInCellsX() const
uint32_t getNumSubscribers() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
static const unsigned char LETHAL_OBSTACLE
bool doAlternativeExploration(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &oldplan)
boost::shared_ptr< ExplorationTransformVis > obstacle_vis_
static const unsigned char NO_INFORMATION
bool getTrajectory(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > goals, std::vector< geometry_msgs::PoseStamped > &plan)
boost::shared_ptr< dynamic_reconfigure::Server< hector_exploration_planner::ExplorationPlannerConfig > > dyn_rec_server_
bool doExploration(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &plan)
bool exploreWalls(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &goals)
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
bool buildexploration_trans_array_(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > goals, bool useAnglePenalty, bool use_cell_danger=true)
double getResolution() const
Costmap2D * getCostmap()
void dynRecParamCallback(hector_exploration_planner::ExplorationPlannerConfig &config, uint32_t level)
float angleDifference(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal)
bool findFrontiersCloseToPath(std::vector< geometry_msgs::PoseStamped > &frontiers)
#define ROS_ERROR(...)
bool doInnerExploration(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &plan)
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
unsigned int getIndex(unsigned int mx, unsigned int my) const
bool findFrontiers(std::vector< geometry_msgs::PoseStamped > &frontiers, std::vector< geometry_msgs::PoseStamped > &noFrontiers)
#define ROS_DEBUG(...)


hector_exploration_planner
Author(s):
autogenerated on Mon Jun 10 2019 13:34:41