21 #ifndef FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_ 22 #define FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_ 30 #include <humanoid_nav_msgs/ClipFootstep.h> 31 #include <sbpl/headers.h> 35 #include <tr1/unordered_set> 36 #include <tr1/hashtable.h> 81 size_t seed = std::tr1::hash<int>()(x.first);
82 return std::tr1::hash<int>()(x.second) + 0x9e3779b9 + (seed<<6) + (seed>>2);
134 std::pair<int, int> updateGoal(
const State& foot_left,
135 const State& foot_right);
142 std::pair<int, int> updateStart(
const State& foot_left,
143 const State& right_right);
151 bool occupied(
const State& s);
158 bool getState(
unsigned int id,
State* s);
171 return ivExpandedStates.begin();
176 return ivExpandedStates.end();
181 return ivRandomStates.begin();
186 return ivRandomStates.end();
193 int GetFromToHeuristic(
int FromStateID,
int ToStateID);
199 int GetGoalHeuristic(
int stateID);
205 int GetStartHeuristic(
int stateID);
212 void GetSuccs(
int SourceStateID, std::vector<int> *SuccIDV,
213 std::vector<int> *CostV);
220 void GetPreds(
int TargetStateID, std::vector<int> *PredIDV,
221 std::vector<int> *CostV);
228 virtual void GetRandomSuccsatDistance(
int SourceStateID,
229 std::vector<int>* SuccIDV,
230 std::vector<int>* CLowV);
237 virtual void GetRandomPredsatDistance(
int TargetStateID,
238 std::vector<int>* PredIDV,
239 std::vector<int>* CLowV);
242 void GetSuccsTo(
int SourceStateID,
int goalStateID,
243 std::vector<int> *SuccIDV, std::vector<int> *CostV);
246 bool AreEquivalent(
int StateID1,
int StateID2);
248 bool InitializeEnv(
const char *sEnvFile);
250 bool InitializeMDPCfg(MDPConfig *MDPCfg);
252 void PrintEnv_Config(FILE *fOut);
254 void PrintState(
int stateID,
bool bVerbose, FILE *fOut);
256 void SetAllActionsandAllOutcomes(CMDPSTATE *state);
258 void SetAllPreds(CMDPSTATE *state);
260 int SizeofCreatedEnv();
270 void getPredsOfGridCells(
const std::vector<State>& changed_states,
271 std::vector<int>* pred_ids);
273 void getSuccsOfGridCells(
const std::vector<State>& changed_states,
274 std::vector<int>* succ_ids);
281 void updateHeuristicValues();
284 static const int cvMmScale = 1000;
302 std::vector<int>* NeighIDV,
303 std::vector<int>* CLowV,
304 int nNumofNeighs,
int nDist_c,
bool bSuccs);
464 #endif // FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_