31 #include <visualization_msgs/Marker.h> 32 #include <visualization_msgs/MarkerArray.h> 33 #include <hector_nav_msgs/GetRobotTrajectory.h> 34 #include <Eigen/Geometry> 36 #include <hector_exploration_planner/ExplorationPlannerConfig.h> 38 #define STRAIGHT_COST 100 39 #define DIAGONAL_COST 141 70 ROS_ERROR(
"[hector_exploration_planner] HectorExplorationPlanner is already initialized_! Please check why initialize() got called twice.");
74 ROS_INFO(
"[hector_exploration_planner] Initializing HectorExplorationPlanner");
88 dyn_rec_server_.reset(
new dynamic_reconfigure::Server<hector_exploration_planner::ExplorationPlannerConfig>(
ros::NodeHandle(
"~/hector_exploration_planner")));
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_);
113 p_alpha_ = config.security_constant;
122 double angle_rad = config.observation_pose_allowed_angle * (M_PI / 180.0);
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.");
141 ROS_INFO(
"[hector_exploration_planner] planning: starting to make a plan to given goal point");
147 std::vector<geometry_msgs::PoseStamped> goals;
154 geometry_msgs::PoseStamped adjusted_goal;
157 ROS_INFO(
"Using observation pose calc.");
159 ROS_ERROR(
"getObservationPose returned false, no area around target point available to drive to!");
163 ROS_INFO(
"Not using observation pose calc.");
165 adjusted_goal = original_goal;
171 goals.push_back(adjusted_goal);
182 plan.push_back(adjusted_goal);
184 costmap_->
worldToMap(adjusted_goal.pose.position.x,adjusted_goal.pose.position.y,mx,my);
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;
199 ROS_INFO(
"[hector_exploration_planner] planning: plan has been found! plansize: %u ", (
unsigned int)plan.size());
215 std::vector<geometry_msgs::PoseStamped> goals;
221 bool frontiers_found =
false;
227 if (!frontiers_found){
228 ROS_WARN(
"Close Exploration desired, but no frontiers found. Falling back to normal exploration!");
240 ROS_INFO(
"[hector_exploration_planner] exploration: found %u frontiers!", (
unsigned int)goals.size());
242 ROS_INFO(
"[hector_exploration_planner] exploration: no frontiers have been found! starting inner-exploration");
252 ROS_INFO(
"[hector_exploration_planner] exploration: could not plan to frontier, starting inner-exploration");
258 geometry_msgs::PoseStamped thisgoal = plan.back();
265 ROS_INFO(
"[hector_exploration_planner] exploration: plan to a frontier has been found! plansize: %u", (
unsigned int)plan.size());
270 ROS_INFO(
"[hector_exploration_planner] inner-exploration: starting exploration");
278 std::vector<geometry_msgs::PoseStamped> goals;
288 ROS_WARN(
"[hector_exploration_planner]: Failed to get RobotPose");
297 double dx = xw - robotPose.getOrigin().getX();
298 double dy = yw - robotPose.getOrigin().getY();
302 if ( (dx*dx + dy*dy) > 0.5*0.5){
304 geometry_msgs::PoseStamped robotPoseMsg;
307 geometry_msgs::PoseStamped goalMsg;
308 goalMsg.pose.position.x = xw;
309 goalMsg.pose.position.y = yw;
310 goalMsg.pose.orientation.w = 1.0;
312 if(
makePlan(robotPoseMsg, goalMsg, plan)){
314 ROS_INFO(
"[hector_exploration_planner] inner-exploration: Planning to previous inner frontier");
323 ROS_INFO(
"[hector_exploration_planner] inner-exploration: found %u inner-frontiers!", (
unsigned int)goals.size());
325 ROS_WARN(
"[hector_exploration_planner] inner-exploration: no inner-frontiers have been found! exploration failed!");
331 ROS_WARN(
"[hector_exploration_planner] inner-exploration: Creating exploration transform failed!");
335 ROS_WARN(
"[hector_exploration_planner] inner-exploration: could not plan to inner-frontier. exploration failed!");
341 int plansize = plan.size() - 5;
343 plan.resize(plansize);
348 const geometry_msgs::PoseStamped& thisgoal = plan.back();
355 ROS_INFO(
"[hector_exploration_planner] inner-exploration: plan to an inner-frontier has been found! plansize: %u", (
unsigned int)plan.size());
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;
372 unsigned int mxs,mys;
373 costmap_->
worldToMap(observation_pose.pose.position.x, observation_pose.pose.position.y, mxs, mys);
375 double pose_yaw =
tf::getYaw(observation_pose.pose.orientation);
377 Eigen::Vector2f obs_pose_dir_vec (cos(pose_yaw), sin(pose_yaw));
383 int min_x = mxs - searchSize/2;
384 int min_y = mys - searchSize/2;
394 int max_x = mxs + searchSize/2;
395 int max_y = mys + searchSize/2;
408 unsigned int closest_sqr_dist = UINT_MAX;
410 bool no_information =
true;
412 for (
int x = min_x;
x < max_x; ++
x){
413 for (
int y = min_y;
y < max_y; ++
y){
421 no_information =
false;
423 int diff_x =
x - (int)mxs;
424 int diff_y =
y - (int)mys;
426 unsigned int sqr_dist = diff_x*diff_x + diff_y*diff_y;
430 if (sqr_dist < closest_sqr_dist){
432 Eigen::Vector2f curr_dir_vec(static_cast<float>(diff_x), static_cast<float>(diff_y));
433 curr_dir_vec.normalize();
437 closest_x = (
unsigned int)
x;
438 closest_y = (
unsigned int)
y;
439 closest_sqr_dist = sqr_dist;
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");
457 if ((closest_x > -1) && (closest_y > -1)){
459 Eigen::Vector2d closest_point_world;
460 costmap_->
mapToWorld(closest_x, closest_y, closest_point_world.x(), closest_point_world.y());
462 Eigen::Vector2d original_goal_pose(observation_pose.pose.position.x, observation_pose.pose.position.y);
465 new_observation_pose.header.frame_id =
"map";
466 new_observation_pose.header.stamp = observation_pose.header.stamp;
468 Eigen::Vector2d dir_vec(original_goal_pose - closest_point_world);
474 new_observation_pose.pose = observation_pose.pose;
475 new_observation_pose.pose.position.z = 0.0;
476 ROS_INFO(
"Observation pose unchanged");
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;
485 double test_distance = distance;
487 Eigen::Vector2d last_valid_pos(closest_point_world);
490 test_distance += 0.1;
492 double distance_factor = test_distance / distance;
494 Eigen::Vector2d new_pos(original_goal_pose - dir_vec*distance_factor);
504 last_valid_pos = new_pos;
506 }
while (test_distance < desired_distance);
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;
513 double angle = std::atan2(dir_vec.y(), dir_vec.x());
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");
525 ROS_ERROR(
"Couldn't find observation pose for given point.");
531 ROS_INFO(
"[hector_exploration_planner] alternative exploration: starting alternative exploration");
537 std::vector<geometry_msgs::PoseStamped> goals;
539 std::vector<geometry_msgs::PoseStamped> old_frontier;
540 old_frontier.push_back(oldplan.back());
547 ROS_INFO(
"[hector_exploration_planner] alternative exploration: found %u frontiers!", (
unsigned int) goals.size());
549 ROS_WARN(
"[hector_exploration_planner] alternative exploration: no frontiers have been found!");
561 const geometry_msgs::PoseStamped& this_goal = plan.back();
566 ROS_INFO(
"[hector_exploration_planner] alternative exploration: plan to a frontier has been found! plansize: %u ", (
unsigned int)plan.size());
572 unsigned int mxs,mys;
578 int goal_proj_x = gx-mxs;
579 int goal_proj_y = gy-mys;
581 float start_angle =
tf::getYaw(start.pose.orientation);
582 float goal_angle = std::atan2(goal_proj_y,goal_proj_x);
584 float both_angle = 0;
585 if(start_angle > goal_angle){
586 both_angle = start_angle - goal_angle;
588 both_angle = goal_angle - start_angle;
597 int startExploreWall = 1;
599 ROS_DEBUG(
"[hector_exploration_planner] wall-follow: exploreWalls");
602 ROS_WARN(
"[hector_exploration_planner] wall-follow: The start coordinates are outside the costmap!");
607 int oldDirection = -1;
612 int adjacentPoints [8];
616 unsigned int minDelta = UINT_MAX;
617 unsigned int maxDelta = 0;
618 unsigned int thisDelta;
619 float minAngle=3.1415;
621 geometry_msgs::PoseStamped trajPoint;
624 if(oldDirection==-1){
626 for (
int i=0; i<8; i++){
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;
645 if (oldDirection == 0){
646 dirPoints[0]=oldDirection+4;
647 dirPoints[1]=oldDirection;
648 dirPoints[2]=oldDirection+7;
650 else if (oldDirection < 3){
651 dirPoints[0]=oldDirection+4;
652 dirPoints[1]=oldDirection;
653 dirPoints[2]=oldDirection+3;
655 else if (oldDirection == 3){
656 dirPoints[0]=oldDirection+4;
657 dirPoints[1]=oldDirection;
658 dirPoints[2]=oldDirection+3;
660 else if (oldDirection == 4){
661 dirPoints[0]=oldDirection-3;
662 dirPoints[1]=oldDirection;
663 dirPoints[2]=oldDirection-4;
665 else if (oldDirection < 7){
666 dirPoints[0]=oldDirection-3;
667 dirPoints[1]=oldDirection;
668 dirPoints[2]=oldDirection-4;
670 else if (oldDirection == 7){
671 dirPoints[0]=oldDirection-7;
672 dirPoints[1]=oldDirection;
673 dirPoints[2]=oldDirection-4;
677 if(startExploreWall == -1){
679 startExploreWall = 0;
680 ROS_INFO(
"[hector_exploration_planner] wall-follow: RHR");
683 startExploreWall = 1;
684 ROS_INFO(
"[hector_exploration_planner] wall-follow: LHR");
691 if(startExploreWall == 1){
692 int temp=dirPoints[0];
693 dirPoints[0]=dirPoints[2];
700 for(
int i=0; i<3; i++){
703 if (thisDelta > 3000 || loop > 7)
705 int plansize = plan.size() - 4;
707 plan.resize(plansize);
709 ROS_DEBUG(
"[hector_exploration_planner] wall-follow: END: exploreWalls. Plansize %d", (
int)plan.size());
710 return !plan.empty();
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];
722 if(thisDelta > maxDelta){
723 maxDelta = thisDelta;
724 nextPoint = adjacentPoints[dirPoints[i]];
725 oldDirection = dirPoints[i];
733 if(thisDelta > maxDelta){
734 maxDelta = thisDelta;
735 nextPoint = adjacentPoints[dirPoints[i]];
736 oldDirection = dirPoints[i];
745 nextPoint=adjacentPoints[dirPoints[2]];
746 oldDirection=dirPoints[2];
749 if(oldDirection==dirPoints[2])
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;
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.5
f);
772 trajPoint.pose.orientation.w = cos(yaw_path*0.5f);
773 plan.push_back(trajPoint);
775 currentPoint=nextPoint;
778 ROS_DEBUG(
"[hector_exploration_planner] wall-follow: END: exploreWalls. Plansize %d", (
int)plan.size());
779 return !plan.empty();
785 #ifdef COSTMAP_2D_LAYERED_COSTMAP_H_ 838 ROS_DEBUG(
"[hector_exploration_planner] buildexploration_trans_array_");
844 std::queue<int> myqueue;
846 size_t num_free_goals = 0;
849 for(
unsigned int i = 0; i < goals.size(); ++i){
867 unsigned int init_cost = 0;
877 ROS_DEBUG(
"[hector_exploration_planner] same frontier: init with 0");
884 myqueue.push(goal_point);
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.");
893 if (use_cell_danger){
894 while(myqueue.size()){
895 int point = myqueue.front();
900 int straightPoints[4];
902 int diagonalPoints[4];
906 for (
int i = 0; i < 4; ++i) {
907 if (
isFree(straightPoints[i])) {
912 myqueue.push(straightPoints[i]);
916 if (
isFree(diagonalPoints[i])) {
921 myqueue.push(diagonalPoints[i]);
927 while(myqueue.size()){
928 int point = myqueue.front();
933 int straightPoints[4];
935 int diagonalPoints[4];
939 for (
int i = 0; i < 4; ++i) {
940 if (
isFree(straightPoints[i])) {
945 myqueue.push(straightPoints[i]);
949 if (
isFree(diagonalPoints[i])) {
954 myqueue.push(diagonalPoints[i]);
961 ROS_DEBUG(
"[hector_exploration_planner] END: buildexploration_trans_array_");
968 ROS_DEBUG(
"[hector_exploration_planner] buildobstacle_trans_array_");
969 std::queue<int> myqueue;
976 }
else if(use_inflated_obstacles){
987 while(myqueue.size()){
988 int point = myqueue.front();
992 if (minimum > obstacle_cutoff_value)
continue;
994 int straightPoints[4];
996 int diagonalPoints[4];
1000 for(
int i = 0; i < 4; ++i){
1003 myqueue.push(straightPoints[i]);
1007 myqueue.push(diagonalPoints[i]);
1012 ROS_DEBUG(
"[hector_exploration_planner] END: buildobstacle_trans_array_");
1020 ROS_DEBUG(
"[hector_exploration_planner] getTrajectory");
1026 ROS_WARN(
"[hector_exploration_planner] The start coordinates are outside the costmap!");
1031 int nextPoint = currentPoint;
1035 geometry_msgs::PoseStamped trajPoint;
1037 trajPoint.header.frame_id = global_frame;
1040 ROS_INFO(
"Already at goal point position. No pose vector generated.");
1046 int adjacentPoints[8];
1051 for(
int i = 0; i < 8; ++i){
1052 if(
isFree(adjacentPoints[i])){
1054 if(thisDelta > maxDelta){
1055 maxDelta = thisDelta;
1056 nextPoint = adjacentPoints[i];
1063 ROS_WARN(
"[hector_exploration_planner] No path to the goal could be found by following gradient!");
1069 unsigned int sx,sy,gx,gy;
1075 trajPoint.pose.position.x = wx;
1076 trajPoint.pose.position.y = wy;
1077 trajPoint.pose.position.z = 0.0;
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.5
f);
1086 trajPoint.pose.orientation.w = cos(yaw_path*0.5f);
1088 plan.push_back(trajPoint);
1090 currentPoint = nextPoint;
1094 ROS_DEBUG(
"[hector_exploration_planner] END: getTrajectory. Plansize %u", (
unsigned int)plan.size());
1095 return !plan.empty();
1099 std::vector<geometry_msgs::PoseStamped> empty_vec;
1113 hector_nav_msgs::GetRobotTrajectory srv_path;
1116 std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
1119 std::vector<geometry_msgs::PoseStamped> goals;
1121 size_t size = traj_vector.size();
1122 ROS_INFO(
"[hector_exploration_planner] Size of trajectory vector for close exploration %u", (
unsigned int)size);
1125 geometry_msgs::PoseStamped lastPose = traj_vector[size-1];
1126 goals.push_back(lastPose);
1130 for(
int i = static_cast<int>(size-2); i >= 0; --i){
1131 const geometry_msgs::PoseStamped& pose = traj_vector[i];
1136 double dx = lastPose.pose.position.x - pose.pose.position.x;
1137 double dy = lastPose.pose.position.y - pose.pose.position.y;
1139 if((dx*dx) + (dy*dy) > (0.25*0.25)){
1140 goals.push_back(pose);
1145 ROS_INFO(
"[hector_exploration_planner] pushed %u goals (trajectory) for close to robot frontier search", (
unsigned int)goals.size());
1150 ROS_WARN(
"[hector_exploration_planner]: Failed to get RobotPose");
1152 geometry_msgs::PoseStamped robotPoseMsg;
1156 ROS_WARN(
"[hector_exploration_planner]: Creating exploration transform array in find inner frontier failed, aborting.");
1170 if(current_val < UINT_MAX){
1172 if (current_val >= explore_threshold){
1173 geometry_msgs::PoseStamped finalFrontier;
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;
1190 frontiers.push_back(finalFrontier);
1197 return frontiers.size() > 0;
1212 std::vector<int> allFrontiers;
1217 allFrontiers.push_back(i);
1221 for(
unsigned int i = 0; i < allFrontiers.size(); ++i){
1223 geometry_msgs::PoseStamped finalFrontier;
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;
1240 frontiers.push_back(finalFrontier);
1245 return (frontiers.size() > 0);
1258 std::vector<int> allFrontiers;
1263 allFrontiers.push_back(i);
1267 for(
unsigned int i = 0; i < allFrontiers.size(); ++i){
1269 geometry_msgs::PoseStamped finalFrontier;
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;
1286 frontiers.push_back(finalFrontier);
1291 return (frontiers.size() > 0);
1296 int nextBlobValue = 1;
1297 std::list<int> usedBlobs;
1299 for(
unsigned int i = 0; i < allFrontiers.size(); ++i){
1302 int currentPoint = allFrontiers[i];
1303 int adjacentPoints[8];
1306 std::list<int> blobs;
1308 for(
int j = 0; j < 8; j++){
1318 usedBlobs.push_back(nextBlobValue);
1322 int blobMergeVal = 0;
1324 for(std::list<int>::iterator adjBlob = blobs.begin(); adjBlob != blobs.end(); ++adjBlob){
1325 if(adjBlob == blobs.begin()){
1326 blobMergeVal = *adjBlob;
1330 for(
unsigned int k = 0; k < allFrontiers.size(); k++){
1332 usedBlobs.remove(*adjBlob);
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;
1350 for(
unsigned int i = 0; i < allFrontiers.size(); ++i){
1351 int point = allFrontiers[i];
1354 current_frontier_size++;
1365 int frontier_point = allFrontiers[max_obs_idx];
1370 bool frontier_is_valid =
true;
1373 frontier_is_valid =
false;
1376 for(
size_t i = 0; i < noFrontiers.size(); ++i){
1377 const geometry_msgs::PoseStamped& noFrontier = noFrontiers[i];
1382 frontier_is_valid =
false;
1386 geometry_msgs::PoseStamped finalFrontier;
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;
1397 if(frontier_is_valid){
1400 frontiers.push_back(finalFrontier);
1404 if(visualization_requested){
1405 visualization_msgs::Marker marker;
1406 marker.header.frame_id =
"map";
1408 marker.ns =
"hector_exploration_planner";
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;
1416 marker.scale.x = 0.2;
1417 marker.scale.y = 0.2;
1418 marker.scale.z = 0.2;
1419 marker.color.a = 1.0;
1421 if(frontier_is_valid){
1422 marker.color.r = 0.0;
1423 marker.color.g = 1.0;
1425 marker.color.r = 1.0;
1426 marker.color.g = 0.0;
1429 marker.color.b = 0.0;
1435 return !frontiers.empty();
1442 hector_nav_msgs::GetRobotTrajectory srv_path;
1445 std::vector<geometry_msgs::PoseStamped>& traj_vector (srv_path.response.trajectory.poses);
1448 std::vector<geometry_msgs::PoseStamped> goals;
1450 size_t size = traj_vector.size();
1451 ROS_DEBUG(
"[hector_exploration_planner] size of trajectory vector %u", (
unsigned int)size);
1454 geometry_msgs::PoseStamped lastPose = traj_vector[size-1];
1455 goals.push_back(lastPose);
1460 bool collision_allowed =
true;
1462 for(
int i = static_cast<int>(size-2); i >= 0; --i){
1463 const geometry_msgs::PoseStamped& pose = traj_vector[i];
1468 double dx = lastPose.pose.position.x - pose.pose.position.x;
1469 double dy = lastPose.pose.position.y - pose.pose.position.y;
1474 if(point_in_free_space){
1475 if((dx*dx) + (dy*dy) > (0.25*0.25)){
1476 goals.push_back(pose);
1478 collision_allowed =
false;
1482 if (!point_in_free_space && !collision_allowed){
1489 ROS_DEBUG(
"[hector_exploration_planner] pushed %u goals (trajectory) for inner frontier-search", (
unsigned int)goals.size());
1494 ROS_WARN(
"[hector_exploration_planner]: Failed to get RobotPose");
1496 geometry_msgs::PoseStamped robotPoseMsg;
1500 ROS_WARN(
"[hector_exploration_planner]: Creating exploration transform array in find inner frontier failed, aborting.");
1513 int max_exploration_trans_point = -1;
1514 unsigned int max_exploration_trans_val = 0;
1521 max_exploration_trans_point = i;
1528 if (max_exploration_trans_point == 0){
1529 ROS_WARN(
"[hector_exploration_planner]: Couldn't find max exploration transform point for inner exploration, aborting.");
1533 geometry_msgs::PoseStamped finalFrontier;
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;
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.5
f);
1551 finalFrontier.pose.orientation.w = cos(yaw_path*0.5f);
1553 innerFrontier.push_back(finalFrontier);
1556 visualization_msgs::Marker marker;
1557 marker.header.frame_id =
"map";
1559 marker.ns =
"hector_exploration_planner";
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;
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;
1591 int adjacentPoints[8];
1594 for(
int i = 0; i < 8; ++i){
1595 if(
isValid(adjacentPoints[i])){
1598 int no_inf_count = 0;
1601 for(
int j = 0; j < 8; j++){
1607 if(no_inf_count > 2){
1683 ROS_WARN(
"[hector_exploration_planner]: Failed to get RobotPose");
1685 geometry_msgs::PoseStamped robotPoseMsg;
1694 double dx = robotPoseMsg.pose.position.x - wfx;
1695 double dy = robotPoseMsg.pose.position.y - wfy;
1698 ROS_DEBUG(
"[hector_exploration_planner]: frontier is within the squared range of: %f", p_dist_for_goal_reached_);
1706 unsigned int fx1,fy1;
1707 unsigned int fx2,fy2;
1715 double dx = wfx1 - wfx2;
1716 double dy = wfy1 - wfy2;
1740 unsigned int mxs,mys;
1746 int goal_proj_x = gx-mxs;
1747 int goal_proj_y = gy-mys;
1749 float start_angle =
tf::getYaw(start.pose.orientation);
1750 float goal_angle = std::atan2(goal_proj_y,goal_proj_x);
1752 float both_angle = 0;
1753 if(start_angle > goal_angle){
1754 both_angle = start_angle - goal_angle;
1756 both_angle = goal_angle - start_angle;
1759 if(both_angle > M_PI){
1760 both_angle = (M_PI - std::abs(start_angle)) + (M_PI - std::abs(goal_angle));
1768 int adjacentPoints[8];
1771 int max_obs_idx = 0;
1772 unsigned int max_obs_dist = 0;
1774 for(
int i = 0; i < 8; ++i){
1775 if(
isValid(adjacentPoints[i])){
1785 int orientationPoint = adjacentPoints[max_obs_idx];
1786 unsigned int sx,sy,gx,gy;
1791 double yaw = std::atan2(y,x);
1798 float angle_fraction = std::pow(angle,3);
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));
1818 points[0] =
left(point);
1819 points[1] =
up(point);
1820 points[2] =
right(point);
1821 points[3] =
down(point);
1827 points[0] =
upleft(point);
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);
1884 if((point >= (
int)
map_width_) && ((point + 1) % (
int)map_width_ != 0)){
1885 return point-map_width_+1;
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
boost::shared_array< bool > is_goal_array_
boost::shared_ptr< ExplorationTransformVis > close_path_vis_
double p_same_frontier_dist_
bool isFrontier(int point)
bool isFrontierReached(int point)
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
ros::Publisher goal_pose_pub_
boost::shared_ptr< ExplorationTransformVis > vis_
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
static double getYaw(const Quaternion &bt_q)
costmap_2d::Costmap2DROS * costmap_ros_
bool buildobstacle_trans_array_(bool use_inflated_obstacles)
bool isSameFrontier(int frontier_point1, int frontier_point2)
boost::shared_array< unsigned int > obstacle_trans_array_
std::string getGlobalFrameID()
bool call(MReq &req, MRes &res)
double p_close_to_path_target_distance_
double getYawToUnknown(int point)
boost::shared_array< unsigned int > exploration_trans_array_
HectorExplorationPlanner()
double p_dist_for_goal_reached_
TFSIMD_FORCE_INLINE const tfScalar & y() const
unsigned int angleDanger(float angle)
unsigned char * getCharMap() const
bool isFreeFrontiers(int point)
boost::shared_ptr< ExplorationTransformVis > inner_vis_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
void getStraightPoints(int point, int points[])
unsigned int cellDanger(int point)
ros::Publisher visualization_pub_
~HectorExplorationPlanner()
ros::Publisher observation_pose_pub_
boost::shared_array< int > frontier_map_array_
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)
unsigned int num_map_cells_
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)
costmap_2d::Costmap2D * costmap_
double p_cos_of_allowed_observation_pose_angle_
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_
bool findInnerFrontier(std::vector< geometry_msgs::PoseStamped > &innerFrontier)
unsigned int getSizeInCellsX() const
uint32_t getNumSubscribers() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
ros::ServiceClient path_service_client_
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)
void getAdjacentPoints(int point, int points[])
boost::shared_ptr< dynamic_reconfigure::Server< hector_exploration_planner::ExplorationPlannerConfig > > dyn_rec_server_
double p_observation_pose_desired_dist_
bool p_use_observation_pose_calculation_
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)
void getDiagonalPoints(int point, int points[])
double getResolution() const
const unsigned char * occupancy_grid_array_
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)
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
bool p_explore_close_to_path_
unsigned int getIndex(unsigned int mx, unsigned int my) const
double p_obstacle_cutoff_dist_
int p_goal_angle_penalty_
bool findFrontiers(std::vector< geometry_msgs::PoseStamped > &frontiers, std::vector< geometry_msgs::PoseStamped > &noFrontiers)