$search
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/footstep_planner/include/footstep_planner/FootstepPlannerEnvironment.h $ 00002 // SVN $Id: FootstepPlannerEnvironment.h 3979 2013-02-26 14:13:46Z garimort@informatik.uni-freiburg.de $ 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 #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 std::vector<std::pair<int, int> > step_range; 00049 double footsize_x, footsize_y, footsize_z; 00050 double foot_origin_shift_x, foot_origin_shift_y; 00051 double max_footstep_x, max_footstep_y, max_footstep_theta; 00052 double max_inverse_footstep_x, max_inverse_footstep_y, 00053 max_inverse_footstep_theta; 00054 double step_cost; 00055 int collision_check_accuracy; 00056 int hash_table_size; 00057 double cell_size; 00058 int num_angle_bins; 00059 bool forward_search; 00060 double max_step_width; 00061 int num_random_nodes; 00062 double random_node_distance; 00063 double heuristic_scale; 00064 }; 00065 00066 00074 class FootstepPlannerEnvironment : public DiscreteSpaceInformation 00075 { 00076 public: 00077 // specialization of hash<int,int>, similar to standard boost::hash on pairs? 00078 struct IntPairHash{ 00079 public: 00080 size_t operator()(std::pair<int, int> x) const throw() { 00081 size_t seed = std::tr1::hash<int>()(x.first); 00082 return std::tr1::hash<int>()(x.second) + 0x9e3779b9 + (seed<<6) + (seed>>2); 00083 } 00084 }; 00085 00086 typedef std::vector<int> exp_states_t; 00087 typedef exp_states_t::const_iterator exp_states_iter_t; 00088 typedef std::tr1::unordered_set<std::pair<int,int>, IntPairHash > exp_states_2d_t; 00089 typedef exp_states_2d_t::const_iterator exp_states_2d_iter_t; 00090 00125 FootstepPlannerEnvironment(const environment_params& params); 00126 00127 virtual ~FootstepPlannerEnvironment(); 00128 00130 void updateGoal(const State& foot_left, const State& foot_right); 00131 00133 void updateStart(const State& foot_left, const State& right_right); 00134 00135 void updateMap(gridmap_2d::GridMap2DPtr map); 00136 00141 bool occupied(const State& s); 00142 00148 bool getState(unsigned int id, State* s); 00149 00154 void reset(); 00155 00157 int getNumExpandedStates() { return ivNumExpandedStates; }; 00158 00159 exp_states_2d_iter_t getExpandedStatesStart() 00160 { 00161 return ivExpandedStates.begin(); 00162 }; 00163 00164 exp_states_2d_iter_t getExpandedStatesEnd() 00165 { 00166 return ivExpandedStates.end(); 00167 }; 00168 00169 exp_states_iter_t getRandomStatesStart() 00170 { 00171 return ivRandomStates.begin(); 00172 }; 00173 00174 exp_states_iter_t getRandomStatesEnd() 00175 { 00176 return ivRandomStates.end(); 00177 }; 00178 00183 int GetFromToHeuristic(int FromStateID, int ToStateID); 00184 00189 int GetGoalHeuristic(int stateID); 00190 00195 int GetStartHeuristic(int stateID); 00196 00202 void GetSuccs(int SourceStateID, std::vector<int> *SuccIDV, 00203 std::vector<int> *CostV); 00204 00210 void GetPreds(int TargetStateID, std::vector<int> *PredIDV, 00211 std::vector<int> *CostV); 00212 00218 virtual void GetRandomSuccsatDistance(int SourceStateID, 00219 std::vector<int>* SuccIDV, 00220 std::vector<int>* CLowV); 00221 00227 virtual void GetRandomPredsatDistance(int TargetStateID, 00228 std::vector<int>* PredIDV, 00229 std::vector<int>* CLowV); 00230 00232 void GetSuccsTo(int SourceStateID, int goalStateID, 00233 std::vector<int> *SuccIDV, std::vector<int> *CostV); 00234 00236 bool AreEquivalent(int StateID1, int StateID2); 00237 00238 bool InitializeEnv(const char *sEnvFile); 00239 00240 bool InitializeMDPCfg(MDPConfig *MDPCfg); 00241 00242 void PrintEnv_Config(FILE *fOut); 00243 00244 void PrintState(int stateID, bool bVerbose, FILE *fOut); 00245 00246 void SetAllActionsandAllOutcomes(CMDPSTATE *state); 00247 00248 void SetAllPreds(CMDPSTATE *state); 00249 00250 int SizeofCreatedEnv(); 00251 00258 bool reachable(const PlanningState& from, const PlanningState& to); 00259 00260 void getPredsOfGridCells(const std::vector<State>& changed_states, 00261 std::vector<int>* pred_ids); 00262 00263 void getSuccsOfGridCells(const std::vector<State>& changed_states, 00264 std::vector<int>* succ_ids); 00265 00271 void updateHeuristicValues(); 00272 00274 static const int cvMmScale = 1000; 00275 00276 protected: 00281 int GetFromToHeuristic(const PlanningState& from, const PlanningState& to); 00282 00284 int stepCost(const PlanningState& a, const PlanningState& b); 00285 00289 bool occupied(const PlanningState& s); 00290 00291 void GetRandomNeighs(const PlanningState* currentState, 00292 std::vector<int>* NeighIDV, 00293 std::vector<int>* CLowV, 00294 int nNumofNeighs, int nDist_c, bool bSuccs); 00295 00297 const PlanningState* createNewHashEntry(const State& s); 00298 00306 const PlanningState* createNewHashEntry(const PlanningState& s); 00307 00309 const PlanningState* getHashEntry(const State& s); 00310 00315 const PlanningState* getHashEntry(const PlanningState& s); 00316 00317 const PlanningState* createHashEntryIfNotExists(const PlanningState& s); 00318 00323 bool closeToGoal(const PlanningState& from); 00324 00329 bool closeToStart(const PlanningState& from); 00330 00337 bool pointWithinPolygon(const std::pair<int, int>& point, 00338 const std::vector<std::pair<int, int> >& edges); 00339 00341 struct less 00342 { 00343 bool operator ()(const PlanningState* a, 00344 const PlanningState* b) const; 00345 }; 00346 00348 int ivIdStartFootLeft; 00350 int ivIdStartFootRight; 00352 int ivIdGoalFootLeft; 00354 int ivIdGoalFootRight; 00355 00360 std::vector<const PlanningState*> ivStateId2State; 00361 00367 std::vector<const PlanningState*>* ivpStateHash2State; 00368 00370 const std::vector<Footstep>& ivFootstepSet; 00371 00373 const boost::shared_ptr<Heuristic> ivHeuristicConstPtr; 00374 00376 const double ivFootsizeX; 00378 const double ivFootsizeY; 00379 00381 const double ivOriginFootShiftX; 00383 const double ivOriginFootShiftY; 00384 00386 const int ivMaxFootstepX; 00388 const int ivMaxFootstepY; 00390 int ivMaxFootstepTheta; 00391 00393 const int ivMaxInvFootstepX; 00395 const int ivMaxInvFootstepY; 00397 int ivMaxInvFootstepTheta; 00398 00403 const int ivStepCost; 00404 00410 const int ivCollisionCheckAccuracy; 00411 00416 const int ivHashTableSize; 00417 00419 const double ivCellSize; 00421 const int ivNumAngleBins; 00422 00424 const bool ivForwardSearch; 00425 00426 double ivMaxStepWidth; 00427 00429 const int ivNumRandomNodes; 00431 const int ivRandomNodeDist; 00432 00437 double ivHeuristicScale; 00438 00439 bool ivHeuristicExpired; 00440 00442 boost::shared_ptr<gridmap_2d::GridMap2D> ivMapPtr; 00443 00444 exp_states_2d_t ivExpandedStates; 00445 exp_states_t ivRandomStates; 00446 size_t ivNumExpandedStates; 00447 00448 bool* ivStepRange; 00449 }; 00450 } 00451 00452 #endif // FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_