Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_
00025 #define FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_
00026
00027 #include <footstep_planner/helper.h>
00028 #include <footstep_planner/PathCostHeuristic.h>
00029 #include <footstep_planner/Heuristic.h>
00030 #include <footstep_planner/Footstep.h>
00031 #include <footstep_planner/PlanningState.h>
00032 #include <footstep_planner/State.h>
00033 #include <humanoid_nav_msgs/ClipFootstep.h>
00034 #include <sbpl/headers.h>
00035
00036 #include <math.h>
00037 #include <vector>
00038 #include <tr1/unordered_set>
00039 #include <tr1/hashtable.h>
00040
00041
00042 namespace footstep_planner
00043 {
00044 struct environment_params
00045 {
00046 std::vector<Footstep> footstep_set;
00047 boost::shared_ptr<Heuristic> heuristic;
00048
00050 std::vector<std::pair<int, int> > step_range;
00051
00052 double footsize_x, footsize_y, footsize_z;
00053 double foot_origin_shift_x, foot_origin_shift_y;
00054 double max_footstep_x, max_footstep_y, max_footstep_theta;
00055 double max_inverse_footstep_x, max_inverse_footstep_y,
00056 max_inverse_footstep_theta;
00057 double step_cost;
00058 int collision_check_accuracy;
00059 int hash_table_size;
00060 double cell_size;
00061 int num_angle_bins;
00062 bool forward_search;
00063 double max_step_width;
00064 int num_random_nodes;
00065 double random_node_distance;
00066 double heuristic_scale;
00067 };
00068
00069
00077 class FootstepPlannerEnvironment : public DiscreteSpaceInformation
00078 {
00079 public:
00080
00081 struct IntPairHash{
00082 public:
00083 size_t operator()(std::pair<int, int> x) const throw() {
00084 size_t seed = std::tr1::hash<int>()(x.first);
00085 return std::tr1::hash<int>()(x.second) + 0x9e3779b9 + (seed<<6) + (seed>>2);
00086 }
00087 };
00088
00089 typedef std::vector<int> exp_states_t;
00090 typedef exp_states_t::const_iterator exp_states_iter_t;
00091 typedef std::tr1::unordered_set<std::pair<int,int>, IntPairHash > exp_states_2d_t;
00092 typedef exp_states_2d_t::const_iterator exp_states_2d_iter_t;
00093
00128 FootstepPlannerEnvironment(const environment_params& params);
00129
00130 virtual ~FootstepPlannerEnvironment();
00131
00137 std::pair<int, int> updateGoal(const State& foot_left,
00138 const State& foot_right);
00139
00145 std::pair<int, int> updateStart(const State& foot_left,
00146 const State& right_right);
00147
00148 void updateMap(gridmap_2d::GridMap2DPtr map);
00149
00154 bool occupied(const State& s);
00155
00161 bool getState(unsigned int id, State* s);
00162
00167 void reset();
00168
00170 int getNumExpandedStates() { return ivNumExpandedStates; };
00171
00172 exp_states_2d_iter_t getExpandedStatesStart()
00173 {
00174 return ivExpandedStates.begin();
00175 };
00176
00177 exp_states_2d_iter_t getExpandedStatesEnd()
00178 {
00179 return ivExpandedStates.end();
00180 };
00181
00182 exp_states_iter_t getRandomStatesStart()
00183 {
00184 return ivRandomStates.begin();
00185 };
00186
00187 exp_states_iter_t getRandomStatesEnd()
00188 {
00189 return ivRandomStates.end();
00190 };
00191
00196 int GetFromToHeuristic(int FromStateID, int ToStateID);
00197
00202 int GetGoalHeuristic(int stateID);
00203
00208 int GetStartHeuristic(int stateID);
00209
00215 void GetSuccs(int SourceStateID, std::vector<int> *SuccIDV,
00216 std::vector<int> *CostV);
00217
00223 void GetPreds(int TargetStateID, std::vector<int> *PredIDV,
00224 std::vector<int> *CostV);
00225
00231 virtual void GetRandomSuccsatDistance(int SourceStateID,
00232 std::vector<int>* SuccIDV,
00233 std::vector<int>* CLowV);
00234
00240 virtual void GetRandomPredsatDistance(int TargetStateID,
00241 std::vector<int>* PredIDV,
00242 std::vector<int>* CLowV);
00243
00245 void GetSuccsTo(int SourceStateID, int goalStateID,
00246 std::vector<int> *SuccIDV, std::vector<int> *CostV);
00247
00249 bool AreEquivalent(int StateID1, int StateID2);
00250
00251 bool InitializeEnv(const char *sEnvFile);
00252
00253 bool InitializeMDPCfg(MDPConfig *MDPCfg);
00254
00255 void PrintEnv_Config(FILE *fOut);
00256
00257 void PrintState(int stateID, bool bVerbose, FILE *fOut);
00258
00259 void SetAllActionsandAllOutcomes(CMDPSTATE *state);
00260
00261 void SetAllPreds(CMDPSTATE *state);
00262
00263 int SizeofCreatedEnv();
00264
00271 bool reachable(const PlanningState& from, const PlanningState& to);
00272
00273 void getPredsOfGridCells(const std::vector<State>& changed_states,
00274 std::vector<int>* pred_ids);
00275
00276 void getSuccsOfGridCells(const std::vector<State>& changed_states,
00277 std::vector<int>* succ_ids);
00278
00284 void updateHeuristicValues();
00285
00287 static const int cvMmScale = 1000;
00288
00289 protected:
00294 int GetFromToHeuristic(const PlanningState& from, const PlanningState& to);
00295
00297 int stepCost(const PlanningState& a, const PlanningState& b);
00298
00302 bool occupied(const PlanningState& s);
00303
00304 void GetRandomNeighs(const PlanningState* currentState,
00305 std::vector<int>* NeighIDV,
00306 std::vector<int>* CLowV,
00307 int nNumofNeighs, int nDist_c, bool bSuccs);
00308
00309 void setStateArea(const PlanningState& left, const PlanningState& right);
00310
00312 const PlanningState* createNewHashEntry(const State& s);
00313
00321 const PlanningState* createNewHashEntry(const PlanningState& s);
00322
00324 const PlanningState* getHashEntry(const State& s);
00325
00330 const PlanningState* getHashEntry(const PlanningState& s);
00331
00332 const PlanningState* createHashEntryIfNotExists(const PlanningState& s);
00333
00338 bool closeToGoal(const PlanningState& from);
00339
00344 bool closeToStart(const PlanningState& from);
00345
00347 struct less
00348 {
00349 bool operator ()(const PlanningState* a,
00350 const PlanningState* b) const;
00351 };
00352
00357 int ivIdPlanningGoal;
00358
00360 int ivIdStartFootLeft;
00362 int ivIdStartFootRight;
00364 int ivIdGoalFootLeft;
00366 int ivIdGoalFootRight;
00367
00368 std::vector<int> ivStateArea;
00369
00374 std::vector<const PlanningState*> ivStateId2State;
00375
00381 std::vector<const PlanningState*>* ivpStateHash2State;
00382
00384 const std::vector<Footstep>& ivFootstepSet;
00385
00387 const boost::shared_ptr<Heuristic> ivHeuristicConstPtr;
00388
00390 const double ivFootsizeX;
00392 const double ivFootsizeY;
00393
00395 const double ivOriginFootShiftX;
00397 const double ivOriginFootShiftY;
00398
00400 const int ivMaxFootstepX;
00402 const int ivMaxFootstepY;
00404 int ivMaxFootstepTheta;
00405
00407 const int ivMaxInvFootstepX;
00409 const int ivMaxInvFootstepY;
00411 int ivMaxInvFootstepTheta;
00412
00417 const int ivStepCost;
00418
00424 const int ivCollisionCheckAccuracy;
00425
00430 const int ivHashTableSize;
00431
00433 const double ivCellSize;
00435 const int ivNumAngleBins;
00436
00438 const bool ivForwardSearch;
00439
00440 double ivMaxStepWidth;
00441
00443 const int ivNumRandomNodes;
00445 const int ivRandomNodeDist;
00446
00451 double ivHeuristicScale;
00452
00454 bool ivHeuristicExpired;
00455
00457 boost::shared_ptr<gridmap_2d::GridMap2D> ivMapPtr;
00458
00459 exp_states_2d_t ivExpandedStates;
00460 exp_states_t ivRandomStates;
00461 size_t ivNumExpandedStates;
00462
00463 bool* ivpStepRange;
00464 };
00465 }
00466
00467 #endif // FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_