$search
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 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. | |
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, int *footstep_x, int *footstep_y) const |
Discretizes the translation of the footstep for a certain (discretized) orientation of a possible state. | |
void | init () |
Initialization method called within the constructor. | |
Private Attributes | |
double | ivCellSize |
The parameter for the discretization of the translation. | |
double | ivContX |
The (continuous) translation in x direction. | |
double | ivContY |
The (continuous) translation in y direction. | |
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. | |
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 43 of file Footstep.h.
typedef std::pair<int, int> footstep_planner::Footstep::footstep_xy [private] |
Typedef representing the (discretized) translation of the footstep.
Definition at line 86 of file Footstep.h.
footstep_planner::Footstep::Footstep | ( | double | x, | |
double | y, | |||
double | theta, | |||
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.
footstep_planner::Footstep::~Footstep | ( | ) |
Definition at line 49 of file Footstep.cpp.
int footstep_planner::Footstep::calculateForwardStep | ( | Leg | leg, | |
int | global_theta, | |||
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. | |
footstep_x | The resulting (discretized) translation in x direction. | |
footstep_y | The resulting (discretized) translation in y direction. |
Definition at line 148 of file Footstep.cpp.
void footstep_planner::Footstep::init | ( | ) | [private] |
Initialization method called within the constructor.
Definition at line 54 of file Footstep.cpp.
PlanningState footstep_planner::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 75 of file Footstep.cpp.
PlanningState footstep_planner::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 112 of file Footstep.cpp.
double footstep_planner::Footstep::ivCellSize [private] |
The parameter for the discretization of the translation.
Definition at line 118 of file Footstep.h.
double footstep_planner::Footstep::ivContX [private] |
The (continuous) translation in x direction.
Definition at line 113 of file Footstep.h.
double footstep_planner::Footstep::ivContY [private] |
The (continuous) translation in y direction.
Definition at line 115 of file Footstep.h.
std::vector<footstep_xy> footstep_planner::Footstep::ivDiscPredecessorLeft [private] |
The reversed (discretized) translation(s) for a left supporting foot.
Definition at line 130 of file Footstep.h.
std::vector<footstep_xy> footstep_planner::Footstep::ivDiscPredecessorRight [private] |
The reversed (discretized) translation(s) for a right supporting foot.
Definition at line 132 of file Footstep.h.
std::vector<footstep_xy> footstep_planner::Footstep::ivDiscSuccessorLeft [private] |
The (discretized) translation(s) for a left supporting foot.
Definition at line 126 of file Footstep.h.
std::vector<footstep_xy> footstep_planner::Footstep::ivDiscSuccessorRight [private] |
The (discretized) translation(s) for a right supporting foot.
Definition at line 128 of file Footstep.h.
int footstep_planner::Footstep::ivMaxHashSize [private] |
The maximal hash size.
Definition at line 123 of file Footstep.h.
int footstep_planner::Footstep::ivNumAngleBins [private] |
The parameter for the discretization of the rotation.
Definition at line 120 of file Footstep.h.
int footstep_planner::Footstep::ivTheta [private] |
The (discretized) rotation of the footstep.
Definition at line 110 of file Footstep.h.