footstep_planner_environment.cpp
Go to the documentation of this file.
00001 #include <vigir_footstep_planner/footstep_planner_environment.h>
00002 
00003 #include <vigir_footstep_planning_plugins/plugin_aggregators/state_generator.h>
00004 
00005 
00006 
00007 namespace vigir_footstep_planning
00008 {
00009 FootstepPlannerEnvironment::FootstepPlannerEnvironment(const EnvironmentParameters& params, const FootPoseTransformer& foot_pose_transformer, boost::function<void (msgs::PlanningFeedback)>& feedback_cb)
00010   : DiscreteSpaceInformation()
00011   , foot_pose_transformer(foot_pose_transformer)
00012   , feedback_cb(feedback_cb)
00013   , params(params)
00014   , ivNumExpandedStates(0)
00015   , frame_id("/world")
00016   , last_feedback_flush(ros::Time::now())
00017 {
00018   state_space.reset(new StateSpace(params, StateID2IndexMapping));
00019 }
00020 
00021 FootstepPlannerEnvironment::~FootstepPlannerEnvironment()
00022 {
00023 }
00024 
00025 void FootstepPlannerEnvironment::setFrameId(const std::string& frame_id)
00026 {
00027   this->frame_id = frame_id;
00028 }
00029 
00030 void FootstepPlannerEnvironment::updateHeuristicValues()
00031 {
00032   // check if start and goal have been set
00033   assert(state_space->ivIdGoalFootLeft != -1 && state_space->ivIdGoalFootRight != -1);
00034   assert(state_space->ivIdStartFootLeft != -1 && state_space->ivIdStartFootRight != -1);
00035 
00036   if (!state_space->ivHeuristicExpired)
00037     return;
00038 
00039   ROS_INFO("Updating the heuristic values.");
00040 
00041 //  if (state_space->ivHeuristicPtr->getHeuristicType() == Heuristic::PATH_STEP_COST_HEURISTIC)
00042 //  {
00043 //    boost::shared_ptr<PathCostHeuristic> h =
00044 //        boost::dynamic_pointer_cast<PathCostHeuristic>(
00045 //          state_space->ivHeuristicPtr);
00046 //    MDPConfig MDPCfg;
00047 //    InitializeMDPCfg(&MDPCfg);
00048 //    const PlanningState* start = state_space->ivStateId2State[MDPCfg.startstateid];
00049 //    const PlanningState* goal = state_space->ivStateId2State[MDPCfg.goalstateid];
00050 
00051 //    // NOTE: start/goal state are set to left leg
00052 //    bool success;
00053 //    if (params.forward_search)
00054 //      success = h->calculateDistances(*start, *goal);
00055 //    else
00056 //      success = h->calculateDistances(*goal, *start);
00057 //    if (!success)
00058 //    {
00059 //      ROS_ERROR("Failed to calculate path cost heuristic.");
00060 //      exit(1);
00061 //    }
00062 //  }
00063 
00064   ROS_DEBUG("Finished updating the heuristic values.");
00065   state_space->ivHeuristicExpired = false;
00066 }
00067 
00068 void FootstepPlannerEnvironment::reset()
00069 {
00070   state_space->reset();
00071 
00072   ivExpandedStates.clear();
00073   ivNumExpandedStates = 0;
00074 
00075   visited_steps.clear();
00076   last_feedback_flush = ros::Time::now();
00077 }
00078 
00079 void FootstepPlannerEnvironment::stateExpanded(const PlanningState& s)
00080 {
00081   ivExpandedStates.insert(std::pair<int,int>(s.getX(), s.getY()));
00082   ++ivNumExpandedStates;
00083 
00084   if (!feedback_cb.empty())
00085   {
00086     if (((ros::Time::now() - last_feedback_flush).toSec()) > 1.0/params.feedback_rate)
00087     {
00088       // send recent visited states
00089       msgs::PlanningFeedback feedback;
00090       feedback.header.stamp = ros::Time::now();
00091       feedback.header.frame_id = frame_id;
00092       feedback.visited_steps = visited_steps;
00093 
00094       // build current plan
00095       const PlanningState* state = &s;
00096       msgs::Step step;
00097       step.header = feedback.header;
00098       step.foot.header = feedback.header;
00099 
00100       feedback.current_step_plan.header = feedback.header;
00101 
00102       while (state)
00103       {
00104         state->getState().getStep(step);
00105         feedback.current_step_plan.steps.push_back(step);
00106 
00107         if (params.forward_search)
00108         {
00109           if (!state->getPredState())
00110             break;
00111           state = state->getPredState();
00112         }
00113         else
00114         {
00115           if (!state->getSuccState())
00116             break;
00117           state = state->getSuccState();
00118         }
00119       }
00120 
00121       // transform step plan
00122       foot_pose_transformer.transformToRobotFrame(feedback.current_step_plan);
00123 
00124       // publish feedback
00125       feedback_cb(feedback);
00126 
00127       visited_steps.clear();
00128       last_feedback_flush = ros::Time::now();
00129     }
00130   }
00131 }
00132 
00133 void FootstepPlannerEnvironment::stateVisited(const PlanningState& s)
00134 {
00135   if (!feedback_cb.empty())
00136   {
00137     msgs::Step step;
00138     s.getState().getStep(step);
00139     step.header.stamp = ros::Time::now();
00140     step.header.frame_id = frame_id;
00141     step.foot.header = step.header;
00142     visited_steps.push_back(step); 
00143   }
00144 }
00145 
00146 int FootstepPlannerEnvironment::GetFromToHeuristic(int FromStateID, int ToStateID)
00147 {
00148   assert(FromStateID >= 0 && (unsigned int) FromStateID < state_space->ivStateId2State.size());
00149   assert(ToStateID >= 0 && (unsigned int) ToStateID < state_space->ivStateId2State.size());
00150 
00151   if ((FromStateID == state_space->ivIdGoalFootLeft && ToStateID == state_space->ivIdGoalFootRight)
00152       || (FromStateID == state_space->ivIdGoalFootRight && ToStateID == state_space->ivIdGoalFootLeft)){
00153     return 0;
00154   }
00155 
00156   return GetFromToHeuristic(*(state_space->ivStateId2State[FromStateID]), *(state_space->ivStateId2State[ToStateID]),
00157                             *(state_space->ivStateId2State[state_space->ivIdPlanningStart]), *(state_space->ivStateId2State[state_space->ivIdPlanningGoal]));
00158 }
00159 
00160 int FootstepPlannerEnvironment::GetFromToHeuristic(const PlanningState& from, const PlanningState& to, const PlanningState& start, const PlanningState& goal)
00161 {
00162   return cvMmScale * params.heuristic_scale * Heuristic::instance().getHeuristicValue(from.getState(), to.getState(), start.getState(), goal.getState());
00163 }
00164 
00165 int FootstepPlannerEnvironment::GetGoalHeuristic(int stateID)
00166 {
00167   const PlanningState* current = state_space->ivStateId2State[stateID];
00168   if (current->getLeg() == LEFT)
00169     return GetFromToHeuristic(stateID, state_space->ivIdGoalFootLeft);
00170   else
00171     return GetFromToHeuristic(stateID, state_space->ivIdGoalFootRight);
00172   //return GetFromToHeuristic(stateID, state_space->ivIdPlanningGoal);
00173 }
00174 
00175 void FootstepPlannerEnvironment::GetPreds(int TargetStateID, std::vector<int> *PredIDV, std::vector<int> *CostV)
00176 {
00177   boost::this_thread::interruption_point();
00178 
00179   PredIDV->clear();
00180   CostV->clear();
00181 
00182   assert(TargetStateID >= 0 && (unsigned int) TargetStateID < state_space->ivStateId2State.size());
00183 
00184   // make start states always absorbing
00185   if (TargetStateID == state_space->ivIdStartFootLeft || TargetStateID == state_space->ivIdStartFootRight)
00186     return;
00187 
00188   const PlanningState* current = state_space->ivStateId2State[TargetStateID];
00189 
00190   if (!current->getSuccState())
00191   {
00192     ROS_WARN("Step cost should be evaluated but current state has no successor!");
00193     return;
00194   }
00195 
00196   // make sure goal state transitions are consistent with
00197   // GetSuccs(some_state, goal_state) where goal_state is reachable by an
00198   // arbitrary step from some_state
00199   if (params.forward_search)
00200   {
00201     if (state_space->ivStateArea.empty())
00202       ROS_WARN("This should not happen! Reactivate setStateArea");
00203     if (TargetStateID == state_space->ivIdGoalFootLeft || TargetStateID == state_space->ivIdGoalFootRight)
00204     {
00205       const PlanningState* s;
00206       int cost;
00207       std::vector<int>::const_iterator state_id_iter;
00208       for(state_id_iter = state_space->ivStateArea.begin(); state_id_iter != state_space->ivStateArea.end(); ++state_id_iter)
00209       {
00210         s = state_space->ivStateId2State[*state_id_iter];
00211         if (s->getLeg() == current->getLeg())
00212           continue;
00213         if (*(current->getSuccState()) == *s)
00214           continue;
00215 
00216         if (!state_space->getStepCost(current->getState(), s->getState(), current->getSuccState()->getState(), cost))
00217           continue;
00218 
00219         PredIDV->push_back(s->getId());
00220         CostV->push_back(cost);
00221         stateVisited(*s);
00222       }
00223       return;
00224     }
00225   }
00226 
00227   stateExpanded(*current);
00228 
00229   // check if start is reachable
00230   if (state_space->closeToStart(*current))
00231   {
00232     const PlanningState* start = state_space->ivStateId2State[state_space->ivIdPlanningStart];
00233     if (*(current->getSuccState()) == *start)
00234       return;
00235 
00236     if (WorldModel::instance().isAccessible(start->getState(), current->getState()))
00237     {
00238       int cost;
00239       if (state_space->getStepCost(current->getState(), start->getState(), current->getSuccState()->getState(), cost))
00240       {
00241         PredIDV->push_back(start->getId());
00242         CostV->push_back(cost);
00243         stateVisited(*start);
00244         return;
00245       }
00246     }
00247   }
00248 
00249   // explorate all states
00250   std::list<PlanningState::Ptr> visited_states = StateGenerator::instance().generatePredecessor(*current);
00251 
00252   PredIDV->reserve(visited_states.size());
00253   CostV->reserve(visited_states.size());
00254 
00255   for (const PlanningState::Ptr& visited_state : visited_states)
00256   {
00257     const PlanningState* successor_hash = state_space->createHashEntryIfNotExists(*visited_state);
00258 
00259     PredIDV->push_back(successor_hash->getId());
00260     CostV->push_back(static_cast<int>(cvMmScale * visited_state->getState().getCost() + 0.5));
00261     stateVisited(*successor_hash);
00262   }
00263 }
00264 
00265 int FootstepPlannerEnvironment::GetStartHeuristic(int stateID)
00266 {
00267   const PlanningState* current = state_space->ivStateId2State[stateID];
00268   if (current->getLeg() == LEFT)
00269     return GetFromToHeuristic(stateID, state_space->ivIdStartFootLeft);
00270   else
00271     return GetFromToHeuristic(stateID, state_space->ivIdStartFootRight);
00272   //return GetFromToHeuristic(stateID, state_space->ivIdPlanningStart);
00273 }
00274 
00275 
00276 void FootstepPlannerEnvironment::GetSuccs(int SourceStateID, std::vector<int> *SuccIDV, std::vector<int> *CostV)
00277 {
00278   boost::this_thread::interruption_point();
00279 
00280   SuccIDV->clear();
00281   CostV->clear();
00282 
00283   assert(SourceStateID >= 0 && unsigned(SourceStateID) < state_space->ivStateId2State.size());
00284 
00285   // make goal states always absorbing
00286   if (SourceStateID == state_space->ivIdGoalFootLeft || SourceStateID == state_space->ivIdGoalFootRight)
00287     return;
00288 
00289   const PlanningState* current = state_space->ivStateId2State[SourceStateID];
00290 
00291   if (!current->getPredState())
00292   {
00293     ROS_WARN("Step cost should be evaluated but current state has no predecessor!");
00294     return;
00295   }
00296 
00297   // make sure start state transitions are consistent with
00298   // GetPreds(some_state, start_state) where some_state is reachable by an
00299   // arbitrary step from start_state
00300   if (!params.forward_search)
00301   {
00302     if (state_space->ivStateArea.empty())
00303       ROS_WARN("This should not happen! Reactivate setStateArea");
00304     if (SourceStateID == state_space->ivIdStartFootLeft || SourceStateID == state_space->ivIdStartFootRight)
00305     {
00306       const PlanningState* s;
00307       int cost;
00308       std::vector<int>::const_iterator state_id_iter;
00309       for(state_id_iter = state_space->ivStateArea.begin(); state_id_iter != state_space->ivStateArea.end(); ++state_id_iter)
00310       {
00311         s = state_space->ivStateId2State[*state_id_iter];
00312         if (s->getLeg() == current->getLeg())
00313           continue;
00314         if (*(current->getPredState()) == *s)
00315           continue;
00316 
00317         if (!state_space->getStepCost(current->getState(), current->getPredState()->getState(), s->getState(), cost))
00318           continue;
00319 
00320         SuccIDV->push_back(s->getId());
00321         CostV->push_back(cost);
00322         stateVisited(*s);
00323       }
00324       return;
00325     }
00326   }
00327 
00328   stateExpanded(*current);
00329 
00330   // check if goal is reachable
00331   if (state_space->closeToGoal(*current))
00332   {
00333     const PlanningState* goal = state_space->ivStateId2State[state_space->ivIdPlanningGoal];
00334     if (*(current->getPredState()) == *goal)
00335       return;
00336 
00337     if (WorldModel::instance().isAccessible(goal->getState(), current->getState()))
00338     {
00339       int cost;
00340       if (state_space->getStepCost(current->getState(), current->getPredState()->getState(), goal->getState(), cost))
00341       {
00342         SuccIDV->push_back(goal->getId());
00343         CostV->push_back(cost);
00344         stateVisited(*goal);
00345         return;
00346       }
00347     }
00348   }
00349 
00350   // explorate all states
00351   std::list<PlanningState::Ptr> visited_states = StateGenerator::instance().generateSuccessor(*current);
00352 
00353   SuccIDV->reserve(visited_states.size());
00354   CostV->reserve(visited_states.size());
00355 
00356   for (const PlanningState::Ptr& visited_state : visited_states)
00357   {
00358     const PlanningState* successor_hash = state_space->createHashEntryIfNotExists(*visited_state);
00359 
00360     SuccIDV->push_back(successor_hash->getId());
00361     CostV->push_back(static_cast<int>(cvMmScale * visited_state->getState().getCost() + 0.5));
00362     stateVisited(*successor_hash);
00363   }
00364 }
00365 
00366 void FootstepPlannerEnvironment::GetRandomSuccsatDistance(int SourceStateID, std::vector<int>* SuccIDV, std::vector<int>* CLowV)
00367 {
00368   boost::this_thread::interruption_point();
00369 
00370   assert(SourceStateID >= 0 && unsigned(SourceStateID) < state_space->ivStateId2State.size());
00371   //goal state should be absorbing
00372   if (SourceStateID == state_space->ivIdGoalFootLeft || SourceStateID == state_space->ivIdGoalFootRight )
00373     return;
00374 
00375 
00376   //const PlanningState* currentState = state_space->ivStateId2State[SourceStateID];
00377   // TODO: state_space->closeToGoal?
00378   //
00379   //            if (state_space->closeToGoal(currentState->getState()))
00380   //                    return;
00381 
00382   //get the successors
00383   //GetRandomNeighs(currentState, SuccIDV, CLowV, params.num_random_nodes, state_space->ivRandomNodeDist, true);
00384 }
00385 
00386 void FootstepPlannerEnvironment::GetRandomPredsatDistance(int TargetStateID, std::vector<int>* PredIDV, std::vector<int>* CLowV)
00387 {
00388   boost::this_thread::interruption_point();
00389 
00390   assert(TargetStateID >= 0 && unsigned(TargetStateID) < state_space->ivStateId2State.size());
00391 
00392   // start state should be absorbing
00393   if (TargetStateID == state_space->ivIdStartFootLeft || TargetStateID == state_space->ivIdStartFootRight)
00394     return;
00395 
00396   //const PlanningState* currentState = state_space->ivStateId2State[TargetStateID];
00397 
00398   // TODO: ???
00399   //            if(state_space->closeToStart(currentState->getState()))
00400   //                    return;
00401 
00402   //get the predecessors
00403   //GetRandomNeighs(currentState, PredIDV, CLowV, params.num_random_nodes, state_space->ivRandomNodeDist, false);
00404 }
00405 
00406 bool FootstepPlannerEnvironment::AreEquivalent(int StateID1, int StateID2)
00407 {
00408   assert(StateID1 >= 0 && StateID2 >= 0 && unsigned(StateID1) < state_space->ivStateId2State.size() && unsigned(StateID2) < state_space->ivStateId2State.size());
00409 
00410   if (StateID1 == StateID2)
00411     return true;
00412 
00413   const PlanningState* s1 = state_space->ivStateId2State[StateID1];
00414   const PlanningState* s2 = state_space->ivStateId2State[StateID2];
00415 
00416   return *s1 == *s2;
00417 }
00418 
00419 bool FootstepPlannerEnvironment::InitializeEnv(const char *sEnvFile)
00420 {
00421   //  ROS_ERROR("FootstepPlanerEnvironment::InitializeEnv: Hit unimplemented "
00422   //            "function. Check this!");
00423   return true;
00424 }
00425 
00426 bool FootstepPlannerEnvironment::InitializeMDPCfg(MDPConfig *MDPCfg)
00427 {
00428   // NOTE: The internal start and goal ids are set here to the left foot
00429   // (this affects the calculation of the heuristic values)
00430   MDPCfg->startstateid = state_space->ivIdPlanningStart;
00431   MDPCfg->goalstateid = state_space->ivIdPlanningGoal;
00432 
00433   assert(state_space->ivIdPlanningStart != -1);
00434   assert(state_space->ivIdPlanningGoal != -1);
00435 
00436   return true;
00437 }
00438 
00439 void FootstepPlannerEnvironment::PrintEnv_Config(FILE *fOut)
00440 {
00441   // NOTE: implement this if the planner needs to print out configurations
00442   ROS_ERROR("FootstepPlanerEnvironment::PrintEnv_Config: Hit "
00443             "unimplemented function. Check this!");
00444 }
00445 
00446 void FootstepPlannerEnvironment::PrintState(int stateID, bool bVerbose, FILE *fOut)
00447 {
00448   if(fOut == NULL)
00449   {
00450     fOut = stdout;
00451   }
00452 
00453   if(stateID == state_space->ivIdGoalFootLeft && bVerbose)
00454   {
00455     SBPL_FPRINTF(fOut, "the state is a goal state\n");
00456   }
00457 
00458   const PlanningState* s = state_space->ivStateId2State[stateID];
00459 
00460   if(bVerbose)
00461   {
00462     SBPL_FPRINTF(fOut, "X=%i Y=%i THETA=%i FOOT=%i\n",
00463                  s->getX(), s->getY(), s->getYaw(), s->getLeg());
00464   }
00465   else
00466   {
00467     SBPL_FPRINTF(fOut, "%i %i %i %i\n",
00468                  s->getX(), s->getY(), s->getYaw(), s->getLeg());
00469   }
00470 }
00471 
00472 void FootstepPlannerEnvironment::SetAllActionsandAllOutcomes(CMDPSTATE *state)
00473 {
00474   // NOTE: not implemented so far
00475   // Description: Some searches may also use SetAllActionsandAllOutcomes
00476   // or SetAllPreds functions if they keep the pointers to successors
00477   // (predecessors) but most searches do not require this, so it is not
00478   // necessary to support this
00479 
00480   ROS_ERROR("FootstepPlannerEnvironment::SetAllActionsandAllOutcomes: Hit"
00481             " unimplemented function. Check this!");
00482 }
00483 
00484 void FootstepPlannerEnvironment::SetAllPreds(CMDPSTATE *state)
00485 {
00486   // NOTE: not implemented so far
00487   // Description: Some searches may also use SetAllActionsandAllOutcomes
00488   // or SetAllPreds functions if they keep the pointers to successors
00489   // (predecessors) but most searches do not require this, so it is not
00490   // necessary to support this
00491 
00492   ROS_ERROR("FootstepPlannerEnvironment::SetAllPreds: Hit unimplemented "
00493             "function. Check this!");
00494 }
00495 
00496 int FootstepPlannerEnvironment::SizeofCreatedEnv()
00497 {
00498   return state_space->ivStateId2State.size();
00499 }
00500 
00501 bool FootstepPlannerEnvironment::less::operator()(const PlanningState* a, const PlanningState* b) const
00502 {
00503   if (a->getX() < b->getX())
00504     return true;
00505   else if (a->getY() < b->getY())
00506     return true;
00507   else if (a->getYaw() < b->getYaw())
00508     return true;
00509   else
00510     return false;
00511 }
00512 }


vigir_footstep_planner
Author(s): Alexander Stumpf
autogenerated on Fri Apr 7 2017 02:59:36