A class representing a footstep (i.e. a translation and rotation of a specific foot with respect to the supporting leg) that can be performed by a humanoid robot. More...
#include <footstep.h>
Public Member Functions | |
| 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 respective discretized footstep based on the parameters of the discretization. | |
| double | getStepCost () const |
| PlanningState | performMeOnThisState (const PlanningState ¤t) const |
| Performs this footstep (translation and rotation) on a given planning state. | |
| PlanningState | reverseMeOnThisState (const PlanningState ¤t) const |
| Reverse this footstep on a given planning state. | |
| ~Footstep () | |
Private Types | |
| typedef std::pair< int, int > | footstep_xy |
| Typedef representing the (discretized) translation of the footstep. | |
Private Member Functions | |
| 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 state. | |
| void | init (double x, double y) |
| Initialization method called within the constructor. | |
Private Attributes | |
| double | ivAngleBinSize |
| double | ivCellSize |
| The parameter for the discretization of the translation. | |
| std::vector< footstep_xy > | ivDiscPredecessorLeft |
| The reversed (discretized) translation(s) for a left supporting foot. | |
| std::vector< footstep_xy > | ivDiscPredecessorRight |
| The reversed (discretized) translation(s) for a right supporting foot. | |
| std::vector< footstep_xy > | ivDiscSuccessorLeft |
| The (discretized) translation(s) for a left supporting foot. | |
| std::vector< footstep_xy > | ivDiscSuccessorRight |
| The (discretized) translation(s) for a right supporting foot. | |
| int | ivMaxHashSize |
| The maximal hash size. | |
| int | ivNumAngleBins |
| The parameter for the discretization of the rotation. | |
| double | ivStepCost |
| int | ivTheta |
| The (discretized) rotation of the footstep. | |
A class representing a footstep (i.e. a translation and rotation of a specific foot with respect to the supporting leg) that can be performed by a humanoid robot.
Since the underlying SBPL is working on discretized states the footsteps are also a discretized translations and rotations.
Definition at line 44 of file footstep.h.
typedef std::pair<int, int> vigir_footstep_planning::Footstep::footstep_xy [private] |
Typedef representing the (discretized) translation of the footstep.
Definition at line 88 of file footstep.h.
| vigir_footstep_planning::Footstep::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 respective discretized footstep based on the parameters of the discretization.
| x | The (continuous) translation in x direction. |
| y | The (continuous) translation in y direction. |
| theta | The (continuous) rotation. |
| cell_size | Parameter to discretize the translation (see PlanningState for further explanation). |
| num_angle_bins | Parameter to discretize the rotation (see PlanningState for further explanation). |
| max_hash_size | The maximal hash size. |
Definition at line 32 of file footstep.cpp.
Definition at line 47 of file footstep.cpp.
| int vigir_footstep_planning::Footstep::calculateForwardStep | ( | Leg | leg, |
| int | global_theta, | ||
| double | x, | ||
| double | y, | ||
| int * | footstep_x, | ||
| int * | footstep_y | ||
| ) | const [private] |
Discretizes the translation of the footstep for a certain (discretized) orientation of a possible state.
| leg | The supporting leg of the possible state. |
| global_theta | The (discretized) orientation of the possible state. |
| x | The (continuous) translation in x direction. |
| y | The (continuous) translation in y direction. |
| footstep_x | The resulting (discretized) translation in x direction. |
| footstep_y | The resulting (discretized) translation in y direction. |
Definition at line 158 of file footstep.cpp.
| double vigir_footstep_planning::Footstep::getStepCost | ( | ) | const [inline] |
Definition at line 84 of file footstep.h.
| void vigir_footstep_planning::Footstep::init | ( | double | x, |
| double | y | ||
| ) | [private] |
Initialization method called within the constructor.
Definition at line 50 of file footstep.cpp.
| PlanningState vigir_footstep_planning::Footstep::performMeOnThisState | ( | const PlanningState & | current | ) | const |
Performs this footstep (translation and rotation) on a given planning state.
| current | The planning state representing the robot's current supporting leg. |
Definition at line 68 of file footstep.cpp.
| PlanningState vigir_footstep_planning::Footstep::reverseMeOnThisState | ( | const PlanningState & | current | ) | const |
Reverse this footstep on a given planning state.
| current | The planning state representing the robot's current supporting leg. |
Definition at line 113 of file footstep.cpp.
double vigir_footstep_planning::Footstep::ivAngleBinSize [private] |
Definition at line 116 of file footstep.h.
double vigir_footstep_planning::Footstep::ivCellSize [private] |
The parameter for the discretization of the translation.
Definition at line 113 of file footstep.h.
std::vector<footstep_xy> vigir_footstep_planning::Footstep::ivDiscPredecessorLeft [private] |
The reversed (discretized) translation(s) for a left supporting foot.
Definition at line 131 of file footstep.h.
std::vector<footstep_xy> vigir_footstep_planning::Footstep::ivDiscPredecessorRight [private] |
The reversed (discretized) translation(s) for a right supporting foot.
Definition at line 133 of file footstep.h.
std::vector<footstep_xy> vigir_footstep_planning::Footstep::ivDiscSuccessorLeft [private] |
The (discretized) translation(s) for a left supporting foot.
Definition at line 127 of file footstep.h.
std::vector<footstep_xy> vigir_footstep_planning::Footstep::ivDiscSuccessorRight [private] |
The (discretized) translation(s) for a right supporting foot.
Definition at line 129 of file footstep.h.
int vigir_footstep_planning::Footstep::ivMaxHashSize [private] |
The maximal hash size.
Definition at line 124 of file footstep.h.
int vigir_footstep_planning::Footstep::ivNumAngleBins [private] |
The parameter for the discretization of the rotation.
Definition at line 115 of file footstep.h.
double vigir_footstep_planning::Footstep::ivStepCost [private] |
Definition at line 121 of file footstep.h.
int vigir_footstep_planning::Footstep::ivTheta [private] |
The (discretized) rotation of the footstep.
Definition at line 119 of file footstep.h.