FootstepPlannerEnvironment.h
Go to the documentation of this file.
1 /*
2  * A footstep planner for humanoid robots
3  *
4  * Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg
5  * http://www.ros.org/wiki/footstep_planner
6  *
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, version 3.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <http://www.gnu.org/licenses/>.
19  */
20 
21 #ifndef FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_
22 #define FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_
23 
29 #include <footstep_planner/State.h>
30 #include <humanoid_nav_msgs/ClipFootstep.h>
31 #include <sbpl/headers.h>
32 
33 #include <math.h>
34 #include <vector>
35 #include <tr1/unordered_set>
36 #include <tr1/hashtable.h>
37 
38 
39 namespace footstep_planner
40 {
42 {
43  std::vector<Footstep> footstep_set;
45 
47  std::vector<std::pair<int, int> > step_range;
48 
54  double step_cost;
57  double cell_size;
64 };
65 
66 
74 class FootstepPlannerEnvironment : public DiscreteSpaceInformation
75 {
76 public:
77  // specialization of hash<int,int>, similar to standard boost::hash on pairs?
78  struct IntPairHash{
79  public:
80  size_t operator()(std::pair<int, int> x) const throw() {
81  size_t seed = std::tr1::hash<int>()(x.first);
82  return std::tr1::hash<int>()(x.second) + 0x9e3779b9 + (seed<<6) + (seed>>2);
83  }
84  };
85 
86  typedef std::vector<int> exp_states_t;
87  typedef exp_states_t::const_iterator exp_states_iter_t;
88  typedef std::tr1::unordered_set<std::pair<int,int>, IntPairHash > exp_states_2d_t;
89  typedef exp_states_2d_t::const_iterator exp_states_2d_iter_t;
90 
126 
127  virtual ~FootstepPlannerEnvironment();
128 
134  std::pair<int, int> updateGoal(const State& foot_left,
135  const State& foot_right);
136 
142  std::pair<int, int> updateStart(const State& foot_left,
143  const State& right_right);
144 
145  void updateMap(gridmap_2d::GridMap2DPtr map);
146 
151  bool occupied(const State& s);
152 
158  bool getState(unsigned int id, State* s);
159 
164  void reset();
165 
167  int getNumExpandedStates() { return ivNumExpandedStates; }
168 
169  exp_states_2d_iter_t getExpandedStatesStart()
170  {
171  return ivExpandedStates.begin();
172  }
173 
174  exp_states_2d_iter_t getExpandedStatesEnd()
175  {
176  return ivExpandedStates.end();
177  }
178 
179  exp_states_iter_t getRandomStatesStart()
180  {
181  return ivRandomStates.begin();
182  }
183 
184  exp_states_iter_t getRandomStatesEnd()
185  {
186  return ivRandomStates.end();
187  }
188 
193  int GetFromToHeuristic(int FromStateID, int ToStateID);
194 
199  int GetGoalHeuristic(int stateID);
200 
205  int GetStartHeuristic(int stateID);
206 
212  void GetSuccs(int SourceStateID, std::vector<int> *SuccIDV,
213  std::vector<int> *CostV);
214 
220  void GetPreds(int TargetStateID, std::vector<int> *PredIDV,
221  std::vector<int> *CostV);
222 
228  virtual void GetRandomSuccsatDistance(int SourceStateID,
229  std::vector<int>* SuccIDV,
230  std::vector<int>* CLowV);
231 
237  virtual void GetRandomPredsatDistance(int TargetStateID,
238  std::vector<int>* PredIDV,
239  std::vector<int>* CLowV);
240 
242  void GetSuccsTo(int SourceStateID, int goalStateID,
243  std::vector<int> *SuccIDV, std::vector<int> *CostV);
244 
246  bool AreEquivalent(int StateID1, int StateID2);
247 
248  bool InitializeEnv(const char *sEnvFile);
249 
250  bool InitializeMDPCfg(MDPConfig *MDPCfg);
251 
252  void PrintEnv_Config(FILE *fOut);
253 
254  void PrintState(int stateID, bool bVerbose, FILE *fOut);
255 
256  void SetAllActionsandAllOutcomes(CMDPSTATE *state);
257 
258  void SetAllPreds(CMDPSTATE *state);
259 
260  int SizeofCreatedEnv();
261 
268  bool reachable(const PlanningState& from, const PlanningState& to);
269 
270  void getPredsOfGridCells(const std::vector<State>& changed_states,
271  std::vector<int>* pred_ids);
272 
273  void getSuccsOfGridCells(const std::vector<State>& changed_states,
274  std::vector<int>* succ_ids);
275 
281  void updateHeuristicValues();
282 
284  static const int cvMmScale = 1000;
285 
286 protected:
291  int GetFromToHeuristic(const PlanningState& from, const PlanningState& to);
292 
294  int stepCost(const PlanningState& a, const PlanningState& b);
295 
299  bool occupied(const PlanningState& s);
300 
301  void GetRandomNeighs(const PlanningState* currentState,
302  std::vector<int>* NeighIDV,
303  std::vector<int>* CLowV,
304  int nNumofNeighs, int nDist_c, bool bSuccs);
305 
306  void setStateArea(const PlanningState& left, const PlanningState& right);
307 
309  const PlanningState* createNewHashEntry(const State& s);
310 
318  const PlanningState* createNewHashEntry(const PlanningState& s);
319 
321  const PlanningState* getHashEntry(const State& s);
322 
327  const PlanningState* getHashEntry(const PlanningState& s);
328 
329  const PlanningState* createHashEntryIfNotExists(const PlanningState& s);
330 
335  bool closeToGoal(const PlanningState& from);
336 
341  bool closeToStart(const PlanningState& from);
342 
344  struct less
345  {
346  bool operator ()(const PlanningState* a,
347  const PlanningState* b) const;
348  };
349 
355 
364 
365  std::vector<int> ivStateArea;
366 
371  std::vector<const PlanningState*> ivStateId2State;
372 
378  std::vector<const PlanningState*>* ivpStateHash2State;
379 
381  const std::vector<Footstep>& ivFootstepSet;
382 
385 
387  const double ivFootsizeX;
389  const double ivFootsizeY;
390 
392  const double ivOriginFootShiftX;
394  const double ivOriginFootShiftY;
395 
397  const int ivMaxFootstepX;
399  const int ivMaxFootstepY;
402 
404  const int ivMaxInvFootstepX;
406  const int ivMaxInvFootstepY;
409 
414  const int ivStepCost;
415 
422 
427  const int ivHashTableSize;
428 
430  const double ivCellSize;
432  const int ivNumAngleBins;
433 
435  const bool ivForwardSearch;
436 
438 
440  const int ivNumRandomNodes;
442  const int ivRandomNodeDist;
443 
449 
452 
455 
456  exp_states_2d_t ivExpandedStates;
457  exp_states_t ivRandomStates;
459 
461 };
462 }
463 
464 #endif // FOOTSTEP_PLANNER_FOOTSTEPPLANNERENVIRONMENT_H_
const int ivStepCost
The costs for each step (discretized with the help of cvMmScale).
std::tr1::unordered_set< std::pair< int, int >, IntPairHash > exp_states_2d_t
const double ivOriginFootShiftX
Shift in x direction from the foot&#39;s center.
const std::vector< Footstep > & ivFootstepSet
The set of footsteps used for the path planning.
const int ivMaxFootstepX
The maximal translation in x direction (discretized in cell size).
boost::shared_ptr< Heuristic > heuristic
std::vector< const PlanningState * > * ivpStateHash2State
Maps from a hash tag to a list of corresponding planning states. (Used in FootstepPlannerEnvironment ...
const double ivFootsizeX
Size of the foot in x direction.
A class defining a footstep planner environment for humanoid robots used by the SBPL to perform plann...
const int ivMaxFootstepY
The maximal translation in y direction (discretized in cell size).
const double ivOriginFootShiftY
Shift in y direction from the foot&#39;s center.
const boost::shared_ptr< Heuristic > ivHeuristicConstPtr
The heuristic function used by the planner.
boost::shared_ptr< gridmap_2d::GridMap2D > ivMapPtr
Pointer to the map.
int ivIdStartFootRight
ID of the start pose of the right foot.
const double ivFootsizeY
Size of the foot in y direction.
int ivIdPlanningGoal
ID of the planning goal, i.e. dependent on the planning direction (forward/backward) this ID is used ...
const int ivMaxInvFootstepY
The minimal translation in y direction (discretized in cell size).
std::vector< const PlanningState * > ivStateId2State
Maps from an ID to the corresponding PlanningState. (Used in the SBPL to access a certain PlanningSta...
A class representing the robot&#39;s pose (i.e. position and orientation) in the (continuous) world view...
Definition: State.h:34
int ivMaxInvFootstepTheta
The minimal rotation (discretized into bins).
exp_states_t ivRandomStates
random intermediate states for R*
const int ivNumRandomNodes
number of random neighbors for R*
int ivMaxFootstepTheta
The maximal rotation (discretized into bins).
int ivIdGoalFootLeft
ID of the goal pose of the left foot.
int ivIdGoalFootRight
ID of the goal pose of the right foot.
bool ivHeuristicExpired
Indicates if heuristic has to be updated.
const double ivCellSize
The size of each grid cell used to discretize the robot positions.
const int ivHashTableSize
Size of the hash table storing the planning states expanded during the search. (Also referred to by m...
const int ivMaxInvFootstepX
The minimal translation in x direction (discretized in cell size).
std::vector< std::pair< int, int > > step_range
Defines the area of performable (discrete) steps.
const int ivCollisionCheckAccuracy
Whether to check just the foot&#39;s inner circle (0), the hole outer circle (1) or exactly the foot&#39;s bo...
const int ivRandomNodeDist
distance of random neighbors for R* (discretized in cells)
A class representing the robot&#39;s pose (i.e. position and orientation) in the underlying SBPL...
Definition: PlanningState.h:45
const int ivNumAngleBins
The number of bins used to discretize the robot orientations.
const bool ivForwardSearch
Whether to use forward search (1) or backward search (0).
int ivIdStartFootLeft
ID of the start pose of the left foot.


footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:24