footstep.h
Go to the documentation of this file.
1 // SVN $HeadURL: https://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_navigation/footstep_planner/include/footstep_planner/Dstar.h $
2 // SVN $Id: Dstar.h 1168 2011-03-30 03:18:02Z hornunga@informatik.uni-freiburg.de $
3 
4 /*
5  * A footstep planner for humanoid robots
6  *
7  * Copyright 2010-2011 Johannes Garimort, Armin Hornung, University of Freiburg
8  * http://www.ros.org/wiki/footstep_planner
9  *
10  * D* Lite (Koenig et al. 2002) partly based on the implementation
11  * by J. Neufeld (http://code.google.com/p/dstarlite/)
12  *
13  *
14  * This program is free software: you can redistribute it and/or modify
15  * it under the terms of the GNU General Public License as published by
16  * the Free Software Foundation, version 3.
17  *
18  * This program is distributed in the hope that it will be useful,
19  * but WITHOUT ANY WARRANTY; without even the implied warranty of
20  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
21  * GNU General Public License for more details.
22  *
23  * You should have received a copy of the GNU General Public License
24  * along with this program. If not, see <http://www.gnu.org/licenses/>.
25  */
26 
27 #ifndef FOOTSTEP_PLANNER_FOOTSTEP_H_
28 #define FOOTSTEP_PLANNER_FOOTSTEP_H_
29 
31 
32 
33 
35 {
44 class Footstep
45 {
46 public:
61  Footstep(double x, double y, double theta, double step_cost, double cell_size, int num_angle_bins, int max_hash_size);
62  ~Footstep();
63 
72  PlanningState performMeOnThisState(const PlanningState& current) const;
73 
82  PlanningState reverseMeOnThisState(const PlanningState& current) const;
83 
84  double getStepCost() const { return ivStepCost; }
85 
86 private:
88  typedef std::pair<int, int> footstep_xy;
89 
91  void init(double x, double y);
92 
110  int calculateForwardStep(Leg leg, int global_theta, double x, double y, int* footstep_x, int* footstep_y) const;
111 
113  double ivCellSize;
117 
119  int ivTheta;
120 
121  double ivStepCost;
122 
125 
127  std::vector<footstep_xy> ivDiscSuccessorLeft;
129  std::vector<footstep_xy> ivDiscSuccessorRight;
131  std::vector<footstep_xy> ivDiscPredecessorLeft;
133  std::vector<footstep_xy> ivDiscPredecessorRight;
134 };
135 } // end of namespace
136 
137 #endif // FOOTSTEP_PLANNER_FOOTSTEP_H_
Footstep(double x, double y, double theta, double step_cost, double cell_size, int num_angle_bins, int max_hash_size)
The constructor takes the continuous translation and rotation of the footstep and calculates the resp...
Definition: footstep.cpp:32
void init(double x, double y)
Initialization method called within the constructor.
Definition: footstep.cpp:50
std::vector< footstep_xy > ivDiscSuccessorRight
The (discretized) translation(s) for a right supporting foot.
Definition: footstep.h:129
PlanningState reverseMeOnThisState(const PlanningState &current) const
Reverse this footstep on a given planning state.
Definition: footstep.cpp:113
std::pair< int, int > footstep_xy
Typedef representing the (discretized) translation of the footstep.
Definition: footstep.h:88
int ivNumAngleBins
The parameter for the discretization of the rotation.
Definition: footstep.h:115
double ivCellSize
The parameter for the discretization of the translation.
Definition: footstep.h:113
std::vector< footstep_xy > ivDiscSuccessorLeft
The (discretized) translation(s) for a left supporting foot.
Definition: footstep.h:127
A class representing the robot&#39;s pose (i.e. position and orientation) in the underlying SBPL...
TFSIMD_FORCE_INLINE const tfScalar & y() const
int ivTheta
The (discretized) rotation of the footstep.
Definition: footstep.h:119
std::vector< footstep_xy > ivDiscPredecessorLeft
The reversed (discretized) translation(s) for a left supporting foot.
Definition: footstep.h:131
A class representing a footstep (i.e. a translation and rotation of a specific foot with respect to t...
Definition: footstep.h:44
PlanningState performMeOnThisState(const PlanningState &current) const
Performs this footstep (translation and rotation) on a given planning state.
Definition: footstep.cpp:68
int ivMaxHashSize
The maximal hash size.
Definition: footstep.h:124
TFSIMD_FORCE_INLINE const tfScalar & x() const
int calculateForwardStep(Leg leg, int global_theta, double x, double y, int *footstep_x, int *footstep_y) const
Discretizes the translation of the footstep for a certain (discretized) orientation of a possible sta...
Definition: footstep.cpp:158
std::vector< footstep_xy > ivDiscPredecessorRight
The reversed (discretized) translation(s) for a right supporting foot.
Definition: footstep.h:133


vigir_footstep_planning_lib
Author(s): Alexander Stumpf
autogenerated on Mon Jun 10 2019 15:47:33