FootstepPlannerEnvironment.cpp
Go to the documentation of this file.
00001 // SVN $HeadURL$
00002 // SVN $Id$
00003 
00004 /*
00005  * A footstep planner for humanoid robots
00006  *
00007  * Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg
00008  * http://www.ros.org/wiki/footstep_planner
00009  *
00010  *
00011  * This program is free software: you can redistribute it and/or modify
00012  * it under the terms of the GNU General Public License as published by
00013  * the Free Software Foundation, version 3.
00014  *
00015  * This program is distributed in the hope that it will be useful,
00016  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00017  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00018  * GNU General Public License for more details.
00019  *
00020  * You should have received a copy of the GNU General Public License
00021  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
00022  */
00023 
00024 #include <footstep_planner/FootstepPlannerEnvironment.h>
00025 
00026 
00027 namespace footstep_planner
00028 {
00029 FootstepPlannerEnvironment::FootstepPlannerEnvironment(
00030     const environment_params& params)
00031 : DiscreteSpaceInformation(),
00032   ivIdPlanningGoal(-1),
00033   ivIdStartFootLeft(-1),
00034   ivIdStartFootRight(-1),
00035   ivIdGoalFootLeft(-1),
00036   ivIdGoalFootRight(-1),
00037   ivpStateHash2State(
00038     new std::vector<const PlanningState*>[params.hash_table_size]),
00039   ivFootstepSet(params.footstep_set),
00040   ivHeuristicConstPtr(params.heuristic),
00041   ivFootsizeX(params.footsize_x),
00042   ivFootsizeY(params.footsize_y),
00043   ivOriginFootShiftX(params.foot_origin_shift_x),
00044   ivOriginFootShiftY(params.foot_origin_shift_y),
00045   ivMaxFootstepX(disc_val(params.max_footstep_x, params.cell_size)),
00046   ivMaxFootstepY(disc_val(params.max_footstep_y, params.cell_size)),
00047   ivMaxFootstepTheta(
00048     angle_state_2_cell(params.max_footstep_theta, params.num_angle_bins)),
00049   ivMaxInvFootstepX(disc_val(params.max_inverse_footstep_x, params.cell_size)),
00050   ivMaxInvFootstepY(disc_val(params.max_inverse_footstep_y, params.cell_size)),
00051   ivMaxInvFootstepTheta(
00052     angle_state_2_cell(params.max_inverse_footstep_theta,
00053                        params.num_angle_bins)),
00054   ivStepCost(cvMmScale * params.step_cost),
00055   ivCollisionCheckAccuracy(params.collision_check_accuracy),
00056   ivHashTableSize(params.hash_table_size),
00057   ivCellSize(params.cell_size),
00058   ivNumAngleBins(params.num_angle_bins),
00059   ivForwardSearch(params.forward_search),
00060   ivMaxStepWidth(double(disc_val(params.max_step_width, params.cell_size))),
00061   ivNumRandomNodes(params.num_random_nodes),
00062   ivRandomNodeDist(params.random_node_distance / ivCellSize),
00063   ivHeuristicScale(params.heuristic_scale),
00064   ivHeuristicExpired(true),
00065   ivNumExpandedStates(0)
00066 {
00067   int num_angle_bins_half = ivNumAngleBins / 2;
00068   if (ivMaxFootstepTheta >= num_angle_bins_half)
00069     ivMaxFootstepTheta -= ivNumAngleBins;
00070   if (ivMaxInvFootstepTheta >= num_angle_bins_half)
00071     ivMaxInvFootstepTheta -= ivNumAngleBins;
00072 
00073   int num_x = ivMaxFootstepX - ivMaxInvFootstepX + 1;
00074   ivpStepRange = new bool[num_x * (ivMaxFootstepY - ivMaxInvFootstepY + 1)];
00075 
00076   // determine whether a (x,y) translation can be performed by the robot by
00077   // checking if it is within a certain area of performable steps
00078   for (int j = ivMaxInvFootstepY; j <= ivMaxFootstepY; ++j)
00079   {
00080     for (int i = ivMaxInvFootstepX; i <= ivMaxFootstepX; ++i)
00081     {
00082       ivpStepRange[(j - ivMaxInvFootstepY) * num_x + (i - ivMaxInvFootstepX)] =
00083         pointWithinPolygon(i, j, params.step_range);
00084     }
00085   }
00086 }
00087 
00088 
00089 FootstepPlannerEnvironment::~FootstepPlannerEnvironment()
00090 {
00091   reset();
00092   if (ivpStateHash2State)
00093   {
00094     delete[] ivpStateHash2State;
00095     ivpStateHash2State = NULL;
00096   }
00097   if (ivpStepRange)
00098   {
00099     delete[] ivpStepRange;
00100     ivpStepRange = NULL;
00101   }
00102 }
00103 
00104 
00105 std::pair<int, int>
00106 FootstepPlannerEnvironment::updateGoal(const State& foot_left,
00107                                        const State& foot_right)
00108 {
00109   // keep the old IDs
00110   int goal_foot_id_left = ivIdGoalFootLeft;
00111   int goal_foot_id_right = ivIdGoalFootRight;
00112 
00113   // update the states for both feet (if necessary)
00114   const PlanningState* p_foot_left = getHashEntry(foot_left);
00115   if (p_foot_left == NULL)
00116     p_foot_left = createNewHashEntry(foot_left);
00117   const PlanningState* p_foot_right = getHashEntry(foot_right);
00118   if (p_foot_right == NULL)
00119     p_foot_right = createNewHashEntry(foot_right);
00120   ivIdGoalFootLeft = p_foot_left->getId();
00121   ivIdGoalFootRight = p_foot_right->getId();
00122   // check if everything has been set correctly
00123   assert(ivIdGoalFootLeft != -1);
00124   assert(ivIdGoalFootRight != -1);
00125 
00126   // if using the forward search a change of the goal states involves an
00127   // update of the heuristic
00128   if (ivForwardSearch)
00129   {
00130     // check if the goal states have been changed
00131     if (goal_foot_id_left != ivIdGoalFootLeft &&
00132         goal_foot_id_right != ivIdGoalFootRight)
00133     {
00134       ivHeuristicExpired = true;
00135       setStateArea(*p_foot_left, *p_foot_right);
00136     }
00137   }
00138 
00139   return std::pair<int, int>(ivIdGoalFootLeft, ivIdGoalFootRight);
00140 }
00141 
00142 
00143 std::pair<int, int>
00144 FootstepPlannerEnvironment::updateStart(const State& foot_left,
00145                                         const State& foot_right)
00146 {
00147   // keep the old IDs
00148   int start_foot_id_left = ivIdStartFootLeft;
00149   int start_foot_id_right = ivIdStartFootRight;
00150 
00151   // update the states for both feet (if necessary)
00152   const PlanningState* p_foot_left = getHashEntry(foot_left);
00153   if (p_foot_left == NULL)
00154     p_foot_left = createNewHashEntry(foot_left);
00155   const PlanningState* p_foot_right = getHashEntry(foot_right);
00156   if (p_foot_right == NULL)
00157     p_foot_right = createNewHashEntry(foot_right);
00158   ivIdStartFootLeft = p_foot_left->getId();
00159   ivIdStartFootRight = p_foot_right->getId();
00160   // check if everything has been set correctly
00161   assert(ivIdStartFootLeft != -1);
00162   assert(ivIdStartFootRight != -1);
00163 
00164   // if using the backward search a change of the start states involves an
00165   // update of the heuristic
00166   if (!ivForwardSearch)
00167   {
00168     // check if the start states have been changed
00169     if (start_foot_id_left != ivIdStartFootLeft ||
00170         start_foot_id_right != ivIdStartFootRight)
00171     {
00172       ivHeuristicExpired = true;
00173       setStateArea(*p_foot_left, *p_foot_right);
00174     }
00175   }
00176 
00177   return std::pair<int, int>(ivIdStartFootLeft, ivIdStartFootRight);
00178 }
00179 
00180 
00181 const PlanningState*
00182 FootstepPlannerEnvironment::createNewHashEntry(const State& s)
00183 {
00184   PlanningState tmp(s, ivCellSize, ivNumAngleBins, ivHashTableSize);
00185   return createNewHashEntry(tmp);
00186 }
00187 
00188 
00189 const PlanningState*
00190 FootstepPlannerEnvironment::createNewHashEntry(const PlanningState& s)
00191 {
00192   unsigned int state_hash = s.getHashTag();
00193   PlanningState* new_state = new PlanningState(s);
00194 
00195   size_t state_id = ivStateId2State.size();
00196   assert(state_id < (size_t)std::numeric_limits<int>::max());
00197 
00198   // insert the ID of the new state into the corresponding map
00199   new_state->setId(state_id);
00200   ivStateId2State.push_back(new_state);
00201 
00202   // insert the new state into the hash map at the corresponding position
00203   ivpStateHash2State[state_hash].push_back(new_state);
00204 
00205   int* entry = new int[NUMOFINDICES_STATEID2IND];
00206   StateID2IndexMapping.push_back(entry);
00207   for(int i = 0; i < NUMOFINDICES_STATEID2IND; ++i)
00208   {
00209     StateID2IndexMapping[state_id][i] = -1;
00210   }
00211 
00212   assert(StateID2IndexMapping.size() - 1 == state_id);
00213 
00214   return new_state;
00215 }
00216 
00217 
00218 const PlanningState*
00219 FootstepPlannerEnvironment::getHashEntry(const State& s)
00220 {
00221   PlanningState tmp(s, ivCellSize, ivNumAngleBins, ivHashTableSize);
00222   return getHashEntry(tmp);
00223 }
00224 
00225 
00226 const PlanningState*
00227 FootstepPlannerEnvironment::getHashEntry(const PlanningState& s)
00228 {
00229   unsigned int state_hash = s.getHashTag();
00230   std::vector<const PlanningState*>::const_iterator state_iter;
00231   for (state_iter = ivpStateHash2State[state_hash].begin();
00232        state_iter != ivpStateHash2State[state_hash].end();
00233        ++state_iter)
00234   {
00235     if (*(*state_iter) == s)
00236       return *state_iter;
00237   }
00238 
00239   return NULL;
00240 }
00241 
00242 const PlanningState*
00243 FootstepPlannerEnvironment::createHashEntryIfNotExists(
00244     const PlanningState& s)
00245 {
00246   const PlanningState* hash_entry = getHashEntry(s);
00247   if (hash_entry == NULL)
00248     hash_entry = createNewHashEntry(s);
00249 
00250   return hash_entry;
00251 
00252 }
00253 
00254 
00255 int
00256 FootstepPlannerEnvironment::stepCost(const PlanningState& a,
00257                                      const PlanningState& b)
00258 {
00259   if (a == b)
00260     return 0;
00261 
00262   // NOTE: instead of using cont_val() the calculation is done directly
00263       // here because cont_val() truncates the input length to int
00264   double dist = euclidean_distance(
00265       a.getX(), a.getY(), b.getX(), b.getY()) * ivCellSize;
00266 
00267   return int(cvMmScale * dist) + ivStepCost;
00268 }
00269 
00270 
00271 bool
00272 FootstepPlannerEnvironment::occupied(const State& s)
00273 {
00274   return occupied(PlanningState(s, ivCellSize, ivNumAngleBins,
00275                                 ivHashTableSize));
00276 }
00277 
00278 
00279 bool
00280 FootstepPlannerEnvironment::occupied(const PlanningState& s)
00281 {
00282   double x = cell_2_state(s.getX(), ivCellSize);
00283   double y = cell_2_state(s.getY(), ivCellSize);
00284   // collision check for the planning state
00285   if (ivMapPtr->isOccupiedAt(x,y))
00286     return true;
00287   double theta = angle_cell_2_state(s.getTheta(), ivNumAngleBins);
00288   double theta_cos = cos(theta);
00289   double theta_sin = sin(theta);
00290 
00291   // transform the planning state to the foot center
00292   x += theta_cos*ivOriginFootShiftX - theta_sin*ivOriginFootShiftY;
00293   if (s.getLeg() == LEFT)
00294     y += theta_sin*ivOriginFootShiftX + theta_cos*ivOriginFootShiftY;
00295   else // leg == RLEG
00296     y += theta_sin*ivOriginFootShiftX - theta_cos*ivOriginFootShiftY;
00297 
00298   // collision check for the foot center
00299   return collision_check(x, y, theta, ivFootsizeX, ivFootsizeY,
00300                          ivCollisionCheckAccuracy, *ivMapPtr);
00301 }
00302 
00303 
00304 bool
00305 FootstepPlannerEnvironment::getState(unsigned int id, State* s)
00306 {
00307   if (id >= ivStateId2State.size())
00308     return false;
00309 
00310   const PlanningState* planning_state = ivStateId2State[id];
00311   s->setX(cell_2_state(planning_state->getX(), ivCellSize));
00312   s->setY(cell_2_state(planning_state->getY(), ivCellSize));
00313   s->setTheta(angles::normalize_angle(angle_cell_2_state(
00314       planning_state->getTheta(), ivNumAngleBins)));
00315   s->setLeg(planning_state->getLeg());
00316 
00317   return true;
00318 }
00319 
00320 
00321 void
00322 FootstepPlannerEnvironment::updateMap(gridmap_2d::GridMap2DPtr map)
00323 {
00324   ivMapPtr.reset();
00325   ivMapPtr = map;
00326 
00327   if (ivHeuristicConstPtr->getHeuristicType() == Heuristic::PATH_COST)
00328   {
00329     boost::shared_ptr<PathCostHeuristic> h =
00330         boost::dynamic_pointer_cast<PathCostHeuristic>(
00331             ivHeuristicConstPtr);
00332     h->updateMap(map);
00333 
00334     ivHeuristicExpired = true;
00335   }
00336 }
00337 
00338 
00339 void
00340 FootstepPlannerEnvironment::updateHeuristicValues()
00341 {
00342   // check if start and goal have been set
00343   assert(ivIdGoalFootLeft != -1 && ivIdGoalFootRight != -1);
00344   assert(ivIdStartFootLeft != -1 && ivIdStartFootRight != -1);
00345 
00346   if (!ivHeuristicExpired)
00347     return;
00348 
00349   ROS_INFO("Updating the heuristic values.");
00350 
00351   if (ivHeuristicConstPtr->getHeuristicType() == Heuristic::PATH_COST)
00352   {
00353     boost::shared_ptr<PathCostHeuristic> h =
00354         boost::dynamic_pointer_cast<PathCostHeuristic>(
00355             ivHeuristicConstPtr);
00356     MDPConfig MDPCfg;
00357     InitializeMDPCfg(&MDPCfg);
00358     const PlanningState* start = ivStateId2State[MDPCfg.startstateid];
00359     const PlanningState* goal = ivStateId2State[MDPCfg.goalstateid];
00360 
00361     // NOTE: start/goal state are set to left leg
00362     bool success;
00363     if (ivForwardSearch)
00364       success = h->calculateDistances(*start, *goal);
00365     else
00366       success = h->calculateDistances(*goal, *start);
00367     if (!success)
00368     {
00369       ROS_ERROR("Failed to calculate path cost heuristic.");
00370       exit(1);
00371     }
00372   }
00373 
00374   ROS_DEBUG("Finished updating the heuristic values.");
00375   ivHeuristicExpired = false;
00376 }
00377 
00378 
00379 void
00380 FootstepPlannerEnvironment::reset()
00381 {
00382   for(unsigned int i = 0; i < ivStateId2State.size(); ++i)
00383   {
00384     if (ivStateId2State[i])
00385     {
00386       delete ivStateId2State[i];
00387     }
00388   }
00389   ivStateId2State.clear();
00390 
00391   if (ivpStateHash2State)
00392   {
00393     for(int i = 0; i < ivHashTableSize; ++i)
00394       ivpStateHash2State[i].clear();
00395   }
00396 
00397   StateID2IndexMapping.clear();
00398 
00399   ivExpandedStates.clear();
00400   ivNumExpandedStates = 0;
00401   ivRandomStates.clear();
00402 
00403   ivIdPlanningGoal = -1;
00404 
00405   ivIdGoalFootLeft = -1;
00406   ivIdGoalFootRight = -1;
00407   ivIdStartFootLeft = -1;
00408   ivIdStartFootRight = -1;
00409 
00410   ivHeuristicExpired = true;
00411 }
00412 
00413 
00414 bool
00415 FootstepPlannerEnvironment::closeToStart(const PlanningState& from)
00416 {
00417   // NOTE: "goal check" for backward planning
00418   const PlanningState* start;
00419   if (from.getLeg() == RIGHT)
00420     start = ivStateId2State[ivIdStartFootLeft];
00421   else
00422     start = ivStateId2State[ivIdStartFootRight];
00423 
00424   return reachable(*start, from);
00425 }
00426 
00427 
00428 bool
00429 FootstepPlannerEnvironment::closeToGoal(const PlanningState& from)
00430 {
00431   // NOTE: "goal check" for forward planning
00432   const PlanningState* goal;
00433   if (from.getLeg() == RIGHT)
00434     goal = ivStateId2State[ivIdGoalFootLeft];
00435   else
00436     goal = ivStateId2State[ivIdGoalFootRight];
00437 
00438   // TODO: check step if reachable == True
00439   return reachable(from, *goal);
00440 }
00441 
00442 
00443 bool
00444 FootstepPlannerEnvironment::reachable(const PlanningState& from,
00445                                       const PlanningState& to)
00446 {
00447   if (euclidean_distance(from.getX(), from.getY(), to.getX(), to.getY()) >
00448       ivMaxStepWidth)
00449   {
00450       return false;
00451   }
00452 
00453   tf::Transform step =
00454     tf::Pose(
00455       tf::createQuaternionFromYaw(
00456         angle_cell_2_state(from.getTheta(), ivNumAngleBins)),
00457       tf::Point(cell_2_state(from.getX(), ivCellSize),
00458                 cell_2_state(from.getY(), ivCellSize),
00459                 0.0)).inverse() *
00460     tf::Pose(
00461       tf::createQuaternionFromYaw(
00462         angle_cell_2_state(from.getTheta(), ivNumAngleBins)),
00463       tf::Point(cell_2_state(to.getX(), ivCellSize),
00464                 cell_2_state(to.getY(), ivCellSize),
00465                 0.0));
00466   int footstep_x = disc_val(step.getOrigin().x(), ivCellSize);
00467   int footstep_y = disc_val(step.getOrigin().y(), ivCellSize);
00468 
00469   // calculate the footstep rotation
00470   int footstep_theta = to.getTheta() - from.getTheta();
00471   // transform the value into [-ivNumAngleBins/2..ivNumAngleBins/2)
00472   int num_angle_bins_half = ivNumAngleBins / 2;
00473   if (footstep_theta >= num_angle_bins_half)
00474     footstep_theta -= ivNumAngleBins;
00475   else if (footstep_theta < -num_angle_bins_half)
00476     footstep_theta += ivNumAngleBins;
00477 
00478   // adjust for the left foot
00479   if (from.getLeg() == LEFT)
00480   {
00481     footstep_y = -footstep_y;
00482     footstep_theta = -footstep_theta;
00483   }
00484 
00485   // check if footstep_x is not within the executable range
00486   if (footstep_x > ivMaxFootstepX || footstep_x < ivMaxInvFootstepX)
00487       return false;
00488   // check if footstep_y is not within the executable range
00489   if (footstep_y > ivMaxFootstepY || footstep_y < ivMaxInvFootstepY)
00490       return false;
00491   // check if footstep_theta is not within the executable range
00492   if (footstep_theta > ivMaxFootstepTheta ||
00493       footstep_theta < ivMaxInvFootstepTheta)
00494       return false;
00495   return ivpStepRange[(footstep_y - ivMaxInvFootstepY) *
00496                       (ivMaxFootstepX - ivMaxInvFootstepX + 1) +
00497                       (footstep_x - ivMaxInvFootstepX)];
00498 
00499 //  // get the (continuous) orientation of state 'from'
00500 //  double orient = -(angle_cell_2_state(from.getTheta(), ivNumAngleBins));
00501 //  double orient_cos = cos(orient);
00502 //  double orient_sin = sin(orient);
00503 //
00504 //  // calculate the footstep shift and rotate it into the 'from'-view
00505 //  int footstep_x = to.getX() - from.getX();
00506 //  int footstep_y = to.getY() - from.getY();
00507 //  double shift_x = footstep_x * orient_cos - footstep_y * orient_sin;
00508 //  double shift_y = footstep_x * orient_sin + footstep_y * orient_cos;
00509 //  footstep_x = round(shift_x);
00510 //  footstep_y = round(shift_y);
00511 //
00512 //  // calculate the footstep rotation
00513 //  int footstep_theta = to.getTheta() - from.getTheta();
00514 //
00515 //  // transform the value into [-ivNumAngleBins/2..ivNumAngleBins/2)
00516 //  int num_angle_bins_half = ivNumAngleBins / 2;
00517 //  if (footstep_theta >= num_angle_bins_half)
00518 //    footstep_theta -= ivNumAngleBins;
00519 //  else if (footstep_theta < -num_angle_bins_half)
00520 //    footstep_theta += ivNumAngleBins;
00521 //
00522 //  // adjust for the left foot
00523 //  if (from.getLeg() == LEFT)
00524 //  {
00525 //    footstep_y = -footstep_y;
00526 //    footstep_theta = -footstep_theta;
00527 //  }
00528 //
00529 //  return (footstep_x <= ivMaxFootstepX &&
00530 //          footstep_x >= ivMaxInvFootstepX &&
00531 //          footstep_y <= ivMaxFootstepY &&
00532 //          footstep_y >= ivMaxInvFootstepY &&
00533 //          footstep_theta <= ivMaxFootstepTheta &&
00534 //          footstep_theta >= ivMaxInvFootstepTheta);
00535 }
00536 
00537 
00538 void
00539 FootstepPlannerEnvironment::getPredsOfGridCells(
00540     const std::vector<State>& changed_states,
00541     std::vector<int>* pred_ids)
00542 {
00543   pred_ids->clear();
00544 
00545   std::vector<State>::const_iterator state_iter;
00546   for (state_iter = changed_states.begin();
00547       state_iter != changed_states.end();
00548       ++state_iter)
00549   {
00550     PlanningState s(*state_iter, ivCellSize, ivNumAngleBins,
00551                     ivHashTableSize);
00552     // generate predecessor planning states
00553     std::vector<Footstep>::const_iterator footstep_set_iter;
00554     for(footstep_set_iter = ivFootstepSet.begin();
00555         footstep_set_iter != ivFootstepSet.end();
00556         ++footstep_set_iter)
00557     {
00558       PlanningState pred = footstep_set_iter->reverseMeOnThisState(s);
00559       // check if predecessor exists
00560       const PlanningState* pred_hash_entry = getHashEntry(pred);
00561       if (pred_hash_entry == NULL)
00562         continue;
00563       pred_ids->push_back(pred_hash_entry->getId());
00564     }
00565   }
00566 }
00567 
00568 
00569 void
00570 FootstepPlannerEnvironment::getSuccsOfGridCells(
00571     const std::vector<State>& changed_states,
00572     std::vector<int>* succ_ids)
00573 {
00574   succ_ids->clear();
00575 
00576   std::vector<State>::const_iterator state_iter;
00577   for (state_iter = changed_states.begin();
00578       state_iter != changed_states.end();
00579       ++state_iter)
00580   {
00581     PlanningState s(*state_iter, ivCellSize, ivNumAngleBins,
00582                     ivHashTableSize);
00583     // generate successors
00584     std::vector<Footstep>::const_iterator footstep_set_iter;
00585     for(footstep_set_iter = ivFootstepSet.begin();
00586         footstep_set_iter != ivFootstepSet.end();
00587         ++footstep_set_iter)
00588     {
00589       PlanningState succ = footstep_set_iter->performMeOnThisState(s);
00590       // check if successor exists
00591       const PlanningState* succ_hash_entry = getHashEntry(succ);
00592       if (succ_hash_entry == NULL)
00593         continue;
00594       succ_ids->push_back(succ_hash_entry->getId());
00595     }
00596   }
00597 }
00598 
00599 
00600 int
00601 FootstepPlannerEnvironment::GetFromToHeuristic(int FromStateID,
00602                                                int ToStateID)
00603 {
00604   assert(FromStateID >= 0 && (unsigned int) FromStateID < ivStateId2State.size());
00605   assert(ToStateID >= 0 && (unsigned int) ToStateID < ivStateId2State.size());
00606 
00607   if ((FromStateID == ivIdGoalFootLeft && ToStateID == ivIdGoalFootRight)
00608       || (FromStateID == ivIdGoalFootRight && ToStateID == ivIdGoalFootLeft)){
00609     return 0;
00610   }
00611 
00612   const PlanningState* from = ivStateId2State[FromStateID];
00613   const PlanningState* to = ivStateId2State[ToStateID];
00614   //            if (ivHeuristicConstPtr->getHeuristicType() == Heuristic::PATH_COST){
00615   //                    boost::shared_ptr<PathCostHeuristic> pathCostHeuristic = boost::dynamic_pointer_cast<PathCostHeuristic>(ivHeuristicConstPtr);
00616   //                    pathCostHeuristic->calculateDistances(*from, *to);
00617   //            }
00618   return GetFromToHeuristic(*from, *to);
00619 }
00620 
00621 int
00622 FootstepPlannerEnvironment::GetFromToHeuristic(const PlanningState& from,
00623                                                const PlanningState& to)
00624 {
00625   return cvMmScale * ivHeuristicScale *
00626     ivHeuristicConstPtr->getHValue(from, to);
00627 }
00628 
00629 
00630 int
00631 FootstepPlannerEnvironment::GetGoalHeuristic(int stateID)
00632 {
00633   return GetFromToHeuristic(stateID, ivIdGoalFootLeft);
00634 }
00635 
00636 
00637 void
00638 FootstepPlannerEnvironment::GetPreds(int TargetStateID,
00639                                      std::vector<int> *PredIDV,
00640                                      std::vector<int> *CostV)
00641 {
00642   PredIDV->clear();
00643   CostV->clear();
00644 
00645   assert(TargetStateID >= 0 &&
00646          (unsigned int) TargetStateID < ivStateId2State.size());
00647 
00648   // make goal state absorbing (only left!)
00649   if (TargetStateID == ivIdStartFootLeft)
00650     return;
00651   // add cheap transition from right to left, so right becomes an equivalent
00652   // goal
00653   if (TargetStateID == ivIdStartFootRight)
00654   {
00655     PredIDV->push_back(ivIdStartFootLeft);
00656     CostV->push_back(0.0);
00657     return;
00658   }
00659 
00660   const PlanningState* current = ivStateId2State[TargetStateID];
00661 
00662   // make sure goal state transitions are consistent with
00663   // GetSuccs(some_state, goal_state) where goal_state is reachable by an
00664   // arbitrary step from some_state
00665   if (ivForwardSearch)
00666   {
00667     if (TargetStateID == ivIdGoalFootLeft || TargetStateID == ivIdGoalFootRight)
00668     {
00669       const PlanningState* s;
00670       int cost;
00671       std::vector<int>::const_iterator state_id_iter;
00672       for(state_id_iter = ivStateArea.begin();
00673           state_id_iter != ivStateArea.end();
00674           ++state_id_iter)
00675       {
00676         s = ivStateId2State[*state_id_iter];
00677         cost = stepCost(*current, *s);
00678         PredIDV->push_back(s->getId());
00679         CostV->push_back(cost);
00680       }
00681       return;
00682     }
00683   }
00684 
00685   ivExpandedStates.insert(std::pair<int,int>(current->getX(), current->getY()));
00686   ++ivNumExpandedStates;
00687 
00688   if (closeToStart(*current))
00689   {
00690     // map to the start state id
00691     PredIDV->push_back(ivIdStartFootLeft);
00692     // get actual costs (dependent on whether the start foot is left or right)
00693     int start_id;
00694     if (current->getLeg() == RIGHT)
00695       start_id = ivIdStartFootLeft;
00696     else
00697       start_id = ivIdStartFootRight;
00698     CostV->push_back(stepCost(*current, *ivStateId2State[start_id]));
00699 
00700     return;
00701   }
00702 
00703   PredIDV->reserve(ivFootstepSet.size());
00704   CostV->reserve(ivFootstepSet.size());
00705   std::vector<Footstep>::const_iterator footstep_set_iter;
00706   for(footstep_set_iter = ivFootstepSet.begin();
00707       footstep_set_iter != ivFootstepSet.end();
00708       ++footstep_set_iter)
00709   {
00710     const PlanningState predecessor =
00711         footstep_set_iter->reverseMeOnThisState(*current);
00712     if (occupied(predecessor))
00713       continue;
00714 
00715     const PlanningState* predecessor_hash = createHashEntryIfNotExists(
00716         predecessor);
00717 
00718     int cost = stepCost(*current, *predecessor_hash);
00719     PredIDV->push_back(predecessor_hash->getId());
00720     CostV->push_back(cost);
00721   }
00722 }
00723 
00724 
00725 int
00726 FootstepPlannerEnvironment::GetStartHeuristic(int stateID)
00727 {
00728   return GetFromToHeuristic(stateID, ivIdStartFootLeft);
00729 }
00730 
00731 
00732 void
00733 FootstepPlannerEnvironment::GetSuccs(int SourceStateID,
00734                                      std::vector<int> *SuccIDV,
00735                                      std::vector<int> *CostV)
00736 {
00737   SuccIDV->clear();
00738   CostV->clear();
00739 
00740   assert(SourceStateID >= 0 &&
00741          unsigned(SourceStateID) < ivStateId2State.size());
00742 
00743   // make goal state absorbing (only left!)
00744   if (SourceStateID == ivIdGoalFootLeft)
00745   {
00746     return;
00747   }
00748   // add cheap transition from right to left, so right becomes an
00749   // equivalent goal
00750   if (SourceStateID == ivIdGoalFootRight)
00751   {
00752     SuccIDV->push_back(ivIdGoalFootLeft);
00753     CostV->push_back(0.0);
00754     return;
00755   }
00756 
00757   const PlanningState* current = ivStateId2State[SourceStateID];
00758 
00759   // make sure start state transitions are consistent with
00760   // GetPreds(some_state, start_state) where some_state is reachable by an
00761   // arbitrary step from start_state
00762   if (!ivForwardSearch)
00763   {
00764     if (SourceStateID == ivIdStartFootLeft ||
00765         SourceStateID == ivIdStartFootRight)
00766     {
00767       const PlanningState* s;
00768       int cost;
00769       std::vector<int>::const_iterator state_id_iter;
00770       for(state_id_iter = ivStateArea.begin();
00771           state_id_iter != ivStateArea.end();
00772           ++state_id_iter)
00773       {
00774         s = ivStateId2State[*state_id_iter];
00775         cost = stepCost(*current, *s);
00776         SuccIDV->push_back(s->getId());
00777         CostV->push_back(cost);
00778       }
00779       return;
00780     }
00781   }
00782 
00783   ivExpandedStates.insert(std::pair<int,int>(current->getX(), current->getY()));
00784   ++ivNumExpandedStates;
00785 
00786   if (closeToGoal(*current))
00787   {
00788     int goal_id;
00789     assert(current->getLeg() != NOLEG);
00790     if (current->getLeg() == RIGHT)
00791       goal_id = ivIdGoalFootLeft;
00792     else
00793       goal_id = ivIdGoalFootRight;
00794 
00795     const PlanningState* goal = ivStateId2State[goal_id];
00796     SuccIDV->push_back(goal_id);
00797     CostV->push_back(stepCost(*current, *goal));
00798 
00799     return;
00800   }
00801 
00802   SuccIDV->reserve(ivFootstepSet.size());
00803   CostV->reserve(ivFootstepSet.size());
00804   std::vector<Footstep>::const_iterator footstep_set_iter;
00805   for(footstep_set_iter = ivFootstepSet.begin();
00806       footstep_set_iter != ivFootstepSet.end();
00807       ++footstep_set_iter)
00808   {
00809     PlanningState successor =
00810         footstep_set_iter->performMeOnThisState(*current);
00811     if (occupied(successor))
00812       continue;
00813 
00814     const PlanningState* successor_hash_entry =
00815         createHashEntryIfNotExists(successor);
00816 
00817     int cost = stepCost(*current, *successor_hash_entry);
00818     SuccIDV->push_back(successor_hash_entry->getId());
00819     CostV->push_back(cost);
00820   }
00821 }
00822 
00823 void
00824 FootstepPlannerEnvironment::GetSuccsTo(int SourceStateID, int goalStateId,
00825                                        std::vector<int> *SuccIDV,
00826                                        std::vector<int> *CostV)
00827 {
00828   //return GetSuccs(SourceStateID, SuccIDV, CostV);
00829 
00830   SuccIDV->clear();
00831   CostV->clear();
00832 
00833   assert(SourceStateID >= 0 &&
00834          unsigned(SourceStateID) < ivStateId2State.size());
00835 
00836   // make goal state absorbing
00837   if (SourceStateID == ivIdGoalFootLeft ){
00838     return;
00839   }
00840 
00841   const PlanningState* current = ivStateId2State[SourceStateID];
00842   ivExpandedStates.insert(std::pair<int,int>(current->getX(), current->getY()));
00843   ++ivNumExpandedStates;
00844 
00845   //ROS_INFO("GetSuccsTo %d -> %d: %f", SourceStateID, goalStateId, euclidean_distance(current->getX(), current->getY(), ivStateId2State[goalStateId]->getX(), ivStateId2State[goalStateId]->getY()));
00846 
00847   // add cheap transition from right to left, so right becomes an equivalent goal
00848   if (goalStateId== ivIdGoalFootLeft && SourceStateID == ivIdGoalFootRight && current->getLeg() == RIGHT){
00849     SuccIDV->push_back(ivIdGoalFootLeft);
00850     CostV->push_back(ivStepCost);
00851     return;
00852   }
00853 
00854   if (closeToGoal(*current))
00855   {
00856     int goal_id;
00857     assert(current->getLeg() != NOLEG);
00858     if (current->getLeg() == RIGHT){
00859       goal_id = ivIdGoalFootLeft;
00860     } else {
00861       goal_id = ivIdGoalFootRight;
00862     }
00863 
00864     const PlanningState* goal = ivStateId2State[goal_id];
00865     int cost = stepCost(*current, *goal);
00866     SuccIDV->push_back(goal_id);
00867     CostV->push_back(cost);
00868 
00869     return;
00870   }
00871 
00872   // intermediate goal reachable (R*)?
00873   assert(goalStateId >= 0 && unsigned(goalStateId) < ivStateId2State.size());
00874   const PlanningState* randomGoal = ivStateId2State[goalStateId];
00875   if (randomGoal->getLeg() != current->getLeg() && reachable(*current, *randomGoal)){
00876     int cost = stepCost(*current, *randomGoal);
00877     SuccIDV->push_back(goalStateId);
00878     CostV->push_back(cost);
00879     //                  ROS_INFO("%d %d", goalStateId, cost);
00880 
00881     //                  return;
00882   }
00883 
00884 
00885   SuccIDV->reserve(ivFootstepSet.size());
00886   CostV->reserve(ivFootstepSet.size());
00887   std::vector<Footstep>::const_iterator footstep_set_iter;
00888   for(footstep_set_iter = ivFootstepSet.begin();
00889       footstep_set_iter != ivFootstepSet.end();
00890       ++footstep_set_iter)
00891   {
00892     PlanningState successor =
00893         footstep_set_iter->performMeOnThisState(*current);
00894     if (occupied(successor))
00895       continue;
00896 
00897     const PlanningState* successor_hash = createHashEntryIfNotExists(successor);
00898 
00899     int cost = stepCost(*current, *successor_hash);
00900     SuccIDV->push_back(successor_hash->getId());
00901     CostV->push_back(cost);
00902   }
00903 }
00904 
00905 
00906 void
00907 FootstepPlannerEnvironment::GetRandomSuccsatDistance(int SourceStateID,
00908                                                      std::vector<int>* SuccIDV, std::vector<int>* CLowV)
00909 {
00910 
00911   assert(SourceStateID >= 0 && unsigned(SourceStateID) < ivStateId2State.size());
00912   //goal state should be absorbing
00913   if (SourceStateID == ivIdGoalFootLeft || SourceStateID == ivIdGoalFootRight )
00914     return;
00915 
00916 
00917   const PlanningState* currentState = ivStateId2State[SourceStateID];
00918   // TODO: closeToGoal?
00919   //
00920   //            if (closeToGoal(*currentState))
00921   //                    return;
00922 
00923   //get the successors
00924   GetRandomNeighs(currentState, SuccIDV, CLowV, ivNumRandomNodes,
00925                   ivRandomNodeDist, true);
00926 }
00927 
00928 void
00929 FootstepPlannerEnvironment::GetRandomPredsatDistance(int TargetStateID,
00930                                                      std::vector<int>* PredIDV, std::vector<int>* CLowV)
00931 {
00932 
00933   assert(TargetStateID >= 0 &&
00934                  unsigned(TargetStateID) < ivStateId2State.size());
00935 
00936   // start state should be absorbing
00937   if (TargetStateID == ivIdStartFootLeft || TargetStateID == ivIdStartFootRight)
00938     return;
00939 
00940   const PlanningState* currentState = ivStateId2State[TargetStateID];
00941 
00942   // TODO: ???
00943   //            if(closeToStart(*currentState))
00944   //                    return;
00945 
00946   //get the predecessors
00947   GetRandomNeighs(currentState, PredIDV, CLowV, ivNumRandomNodes,
00948                   ivRandomNodeDist, false);
00949 
00950 }
00951 
00952 //generates nNumofNeighs random neighbors of cell <X,Y> at distance nDist_c (measured in cells)
00953 //it will also generate goal if within this distance as an additional neighbor
00954 //bSuccs is set to true if we are computing successor states, otherwise it is Preds
00955 // (see fct. implemented in environment_nav2D)
00956 void FootstepPlannerEnvironment::GetRandomNeighs(const PlanningState* currentState, std::vector<int>* NeighIDV, std::vector<int>* CLowV, int nNumofNeighs, int nDist_c, bool bSuccs)
00957 {
00958 
00959   //clear the successor array
00960   NeighIDV->clear();
00961   CLowV->clear();
00962 
00963 
00964   //get X, Y for the states
00965   int X = currentState->getX();
00966   int Y = currentState->getY();
00967   //int theta = currentState->getTheta();
00968 
00969   //see if the goal/start belongs to the inside area and if yes then add it to Neighs as well
00970   // NOTE: "goal check" for backward planning
00971   const PlanningState* goal_left = NULL;
00972   const PlanningState* goal_right = NULL;
00973   if (bSuccs){
00974     goal_left = ivStateId2State[ivIdGoalFootLeft];
00975     goal_right = ivStateId2State[ivIdGoalFootRight];
00976   } else {
00977     goal_left = ivStateId2State[ivIdStartFootLeft];
00978     goal_right = ivStateId2State[ivIdStartFootRight];
00979   }
00980 
00981   int nDist_sq = nDist_c*nDist_c;
00982 
00983   //add left if within the distance
00984   if (euclidean_distance_sq(X, Y, goal_left->getX(), goal_left->getY()) <= nDist_sq)
00985   {
00986     //compute clow
00987     int clow;
00988     if(bSuccs)
00989       clow = GetFromToHeuristic(*currentState, *goal_left);
00990     else
00991       clow = GetFromToHeuristic(*goal_left, *currentState);
00992 
00993     NeighIDV->push_back(goal_left->getId());
00994     CLowV->push_back(clow);
00995     ivRandomStates.push_back(goal_left->getId());
00996   }
00997 
00998   //add right if within the distance
00999   if(euclidean_distance_sq(X, Y, goal_right->getX(), goal_right->getY()) <= nDist_sq)
01000   {
01001     //compute clow
01002     int clow;
01003     if(bSuccs)
01004       clow = GetFromToHeuristic(*currentState, *goal_right);
01005     else
01006       clow = GetFromToHeuristic(*goal_right, *currentState);
01007 
01008     NeighIDV->push_back(goal_right->getId());
01009     CLowV->push_back(clow);
01010     ivRandomStates.push_back(goal_right->getId());
01011   }
01012 
01013   //iterate through random actions
01014   int nAttempts = 0;
01015   for (int i = 0; i < nNumofNeighs && nAttempts < 5*nNumofNeighs; ++i, ++nAttempts)
01016   {
01017 
01018     // pick goal in random direction
01019     float fDir = (float)(TWO_PI*(((double)rand())/RAND_MAX));
01020 
01021     int dX = (int)(nDist_c*cos(fDir));
01022     int dY = (int)(nDist_c*sin(fDir));
01023 
01024     //get the coords of the state
01025     int newX = X + dX;
01026     int newY = Y + dY;
01027 
01028     // TODO / FIXME x,y, can be negative! need offset
01029     // check if outside of map:
01030     //                  if (newX < 0 || newY < 0 || unsigned(newX) >= ivMapPtr->getInfo().width || unsigned(newY) >= ivMapPtr->getInfo().height){
01031     //                          i--;
01032     //                          ROS_INFO("Outside of map: %d %d", newX, newY);
01033     //                          continue;
01034     //                  }
01035 
01036     // direction of random exploration (facing forward):
01037     int newTheta = angle_state_2_cell(fDir, ivNumAngleBins);
01038 
01039     // random left/right
01040     Leg newLeg = Leg(rand() % 2);
01041 
01042     PlanningState randomState(newX, newY, newTheta, newLeg, ivHashTableSize);
01043 
01044     // add both left and right if available:
01045     //                  int sep = disc_val(0.07, ivCellSize);
01046     //                  int ddX = int(-sin(fDir) * sep);
01047     //                  int ddY = int(cos(fDir) * sep);
01048     //                  PlanningState randomState(newX+ddX, newY+ddY, newTheta, LEFT, ivHashTableSize);
01049     //
01050     //                  PlanningState randomStateR(newX-ddX, newY-ddY, newTheta, RIGHT, ivHashTableSize);
01051 
01052     if(!occupied(randomState))
01053     {
01054       const PlanningState* random_hash_entry = getHashEntry(randomState);
01055       if (random_hash_entry == NULL){
01056         random_hash_entry = createNewHashEntry(randomState);
01057         ivRandomStates.push_back(random_hash_entry->getId());
01058       }
01059 
01060       //compute clow
01061       int clow;
01062       if(bSuccs)
01063         clow = GetFromToHeuristic(currentState->getId(), random_hash_entry->getId());
01064 
01065       else
01066         clow = GetFromToHeuristic(random_hash_entry->getId(), currentState->getId());
01067 
01068       NeighIDV->push_back(random_hash_entry->getId());
01069       CLowV->push_back(clow);
01070 
01071     }else{
01072       i--;
01073     }
01074 
01075     //                  if(!occupied(randomStateR))
01076     //                  {
01077     //                          const PlanningState* random_hash_entry = getHashEntry(randomStateR);
01078     //                          if (random_hash_entry == NULL){
01079     //                                  random_hash_entry = createNewHashEntry(randomStateR);
01080     //                                  ivRandomStates.push_back(random_hash_entry->getId());
01081     //                          }
01082     //
01083     //                          //compute clow
01084     //                          int clow;
01085     //                          if(bSuccs)
01086     //                                  clow = GetFromToHeuristic(currentState->getId(), random_hash_entry->getId());
01087     //                          else
01088     //                                  clow = GetFromToHeuristic(random_hash_entry->getId(), currentState->getId());
01089     //
01090     //                          NeighIDV->push_back(random_hash_entry->getId());
01091     //                          CLowV->push_back(clow);
01092     //
01093     //                  }else{
01094     //                          i--;
01095     //                  }
01096 
01097 
01098   }
01099 
01100   if (NeighIDV->size() == 0){
01101     ROS_WARN("Could not create any random neighbor nodes (%d attempts) from id %d (%d %d)",
01102              nAttempts, currentState->getId(), X, Y);
01103   } else
01104 
01105     ROS_DEBUG("Created %zu random neighbors (%d attempts) from id %d "
01106         "(%d %d)", NeighIDV->size(), nAttempts, currentState->getId(),
01107         X, Y);
01108 }
01109 
01110 bool
01111 FootstepPlannerEnvironment::AreEquivalent(int StateID1, int StateID2)
01112 {
01113   assert(StateID1 >= 0 && StateID2 >= 0
01114          && unsigned(StateID1) < ivStateId2State.size() && unsigned(StateID2) < ivStateId2State.size());
01115 
01116 
01117   if (StateID1 == StateID2)
01118     return true;
01119 
01120   const PlanningState* s1 = ivStateId2State[StateID1];
01121   const PlanningState* s2 = ivStateId2State[StateID2];
01122 
01123   //            // approximately compare, ignore theta:
01124   return (std::abs(s1->getX() - s2->getX()) < 1
01125       && std::abs(s1->getY() - s2->getY()) < 1
01126       //                                        && std::abs(s1->getTheta() - s2->getTheta()) < 3
01127       && s1->getLeg() == s2->getLeg()
01128   );
01129 
01130 
01131 //  compare the actual values (exact comparison)
01132 //  return (*s1 == *s2);
01133 }
01134 
01135 
01136 
01137 bool
01138 FootstepPlannerEnvironment::InitializeEnv(const char *sEnvFile)
01139 {
01140 //  ROS_ERROR("FootstepPlanerEnvironment::InitializeEnv: Hit unimplemented "
01141 //            "function. Check this!");
01142   return true;
01143 }
01144 
01145 
01146 bool
01147 FootstepPlannerEnvironment::InitializeMDPCfg(MDPConfig *MDPCfg)
01148 {
01149   // NOTE: The internal start and goal ids are set here to the left foot
01150   // (this affects the calculation of the heuristic values)
01151   MDPCfg->goalstateid = ivIdGoalFootLeft;
01152   MDPCfg->startstateid = ivIdStartFootLeft;
01153 
01154   assert(ivIdGoalFootLeft != -1);
01155   assert(ivIdStartFootLeft != -1);
01156 
01157   return true;
01158 }
01159 
01160 
01161 void
01162 FootstepPlannerEnvironment::PrintEnv_Config(FILE *fOut)
01163 {
01164   // NOTE: implement this if the planner needs to print out configurations
01165   ROS_ERROR("FootstepPlanerEnvironment::PrintEnv_Config: Hit "
01166       "unimplemented function. Check this!");
01167 }
01168 
01169 
01170 void
01171 FootstepPlannerEnvironment::PrintState(int stateID, bool bVerbose,
01172                                        FILE *fOut)
01173 {
01174   if(fOut == NULL)
01175   {
01176     fOut = stdout;
01177   }
01178 
01179   if(stateID == ivIdGoalFootLeft && bVerbose)
01180   {
01181     SBPL_FPRINTF(fOut, "the state is a goal state\n");
01182   }
01183 
01184   const PlanningState* s = ivStateId2State[stateID];
01185 
01186   if(bVerbose)
01187   {
01188     SBPL_FPRINTF(fOut, "X=%i Y=%i THETA=%i FOOT=%i\n",
01189                  s->getX(), s->getY(), s->getTheta(), s->getLeg());
01190   }
01191   else
01192   {
01193     SBPL_FPRINTF(fOut, "%i %i %i %i\n",
01194                  s->getX(), s->getY(), s->getTheta(), s->getLeg());
01195   }
01196 }
01197 
01198 
01199 void
01200 FootstepPlannerEnvironment::SetAllActionsandAllOutcomes(CMDPSTATE *state)
01201 {
01202   // NOTE: not implemented so far
01203   // Description: Some searches may also use SetAllActionsandAllOutcomes
01204   // or SetAllPreds functions if they keep the pointers to successors
01205   // (predecessors) but most searches do not require this, so it is not
01206   // necessary to support this
01207 
01208   ROS_ERROR("FootstepPlannerEnvironment::SetAllActionsandAllOutcomes: Hit"
01209       " unimplemented function. Check this!");
01210 }
01211 
01212 
01213 void
01214 FootstepPlannerEnvironment::SetAllPreds(CMDPSTATE *state)
01215 {
01216   // NOTE: not implemented so far
01217   // Description: Some searches may also use SetAllActionsandAllOutcomes
01218   // or SetAllPreds functions if they keep the pointers to successors
01219   // (predecessors) but most searches do not require this, so it is not
01220   // necessary to support this
01221 
01222   ROS_ERROR("FootstepPlannerEnvironment::SetAllPreds: Hit unimplemented "
01223       "function. Check this!");
01224 }
01225 
01226 
01227 int
01228 FootstepPlannerEnvironment::SizeofCreatedEnv()
01229 {
01230   return ivStateId2State.size();
01231 }
01232 
01233 
01234 void
01235 FootstepPlannerEnvironment::setStateArea(const PlanningState& left,
01236                                          const PlanningState& right)
01237 {
01238   ivStateArea.clear();
01239 
01240   const PlanningState* p_state = getHashEntry(right);
01241   ivStateArea.push_back(p_state->getId());
01242 
01243   double cont_step_x, cont_step_y, cont_step_theta;
01244   for (int step_y = ivMaxInvFootstepY; step_y <= ivMaxFootstepY; ++step_y)
01245   {
01246     for (int step_x = ivMaxInvFootstepX; step_x <= ivMaxFootstepX; ++step_x)
01247     {
01248       for (int step_theta = ivMaxInvFootstepTheta;
01249            step_theta <= ivMaxFootstepTheta;
01250            ++step_theta)
01251       {
01252         cont_step_x = cont_val(step_x, ivCellSize);
01253         cont_step_y = cont_val(step_y, ivCellSize);
01254         cont_step_theta = angle_cell_2_state(step_theta, ivNumAngleBins);
01255         Footstep step(cont_step_x, cont_step_y, cont_step_theta,
01256                       ivCellSize, ivNumAngleBins, ivHashTableSize);
01257         if (ivForwardSearch)
01258         {
01259           PlanningState pred = step.reverseMeOnThisState(left);
01260           if (occupied(pred) || !reachable(pred, left))
01261             continue;
01262           p_state = createHashEntryIfNotExists(pred);
01263           ivStateArea.push_back(p_state->getId());
01264 
01265           pred = step.reverseMeOnThisState(right);
01266           if (occupied(pred) || !reachable(pred, right))
01267             continue;
01268           p_state = createHashEntryIfNotExists(pred);
01269           ivStateArea.push_back(p_state->getId());
01270         }
01271         else
01272         {
01273           PlanningState succ = step.performMeOnThisState(left);
01274           if (occupied(succ) || !reachable(left, succ))
01275             continue;
01276           p_state = createHashEntryIfNotExists(succ);
01277           ivStateArea.push_back(p_state->getId());
01278 
01279           succ = step.performMeOnThisState(right);
01280           if (occupied(succ) || !reachable(right, succ))
01281             continue;
01282           p_state = createHashEntryIfNotExists(succ);
01283           ivStateArea.push_back(p_state->getId());
01284         }
01285       }
01286     }
01287   }
01288 }
01289 
01290 
01291 bool
01292 FootstepPlannerEnvironment::less::operator ()(const PlanningState* a,
01293                                               const PlanningState* b)
01294 const
01295 {
01296   if (a->getX() < b->getX())
01297     return true;
01298   else if (a->getY() < b->getY())
01299     return true;
01300   else
01301     return false;
01302 }
01303 }
01304 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Tue Oct 15 2013 10:06:51