Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
vigir_footstep_planning::Footstep Class Reference

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. More...
 
double getStepCost () const
 
PlanningState performMeOnThisState (const PlanningState &current) const
 Performs this footstep (translation and rotation) on a given planning state. More...
 
PlanningState reverseMeOnThisState (const PlanningState &current) const
 Reverse this footstep on a given planning state. More...
 
 ~Footstep ()
 

Private Types

typedef std::pair< int, int > footstep_xy
 Typedef representing the (discretized) translation of the footstep. More...
 

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. More...
 
void init (double x, double y)
 Initialization method called within the constructor. More...
 

Private Attributes

double ivAngleBinSize
 
double ivCellSize
 The parameter for the discretization of the translation. More...
 
std::vector< footstep_xyivDiscPredecessorLeft
 The reversed (discretized) translation(s) for a left supporting foot. More...
 
std::vector< footstep_xyivDiscPredecessorRight
 The reversed (discretized) translation(s) for a right supporting foot. More...
 
std::vector< footstep_xyivDiscSuccessorLeft
 The (discretized) translation(s) for a left supporting foot. More...
 
std::vector< footstep_xyivDiscSuccessorRight
 The (discretized) translation(s) for a right supporting foot. More...
 
int ivMaxHashSize
 The maximal hash size. More...
 
int ivNumAngleBins
 The parameter for the discretization of the rotation. More...
 
double ivStepCost
 
int ivTheta
 The (discretized) rotation of the footstep. More...
 

Detailed Description

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.

Member Typedef Documentation

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.

Constructor & Destructor Documentation

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.

Parameters
xThe (continuous) translation in x direction.
yThe (continuous) translation in y direction.
thetaThe (continuous) rotation.
cell_sizeParameter to discretize the translation (see PlanningState for further explanation).
num_angle_binsParameter to discretize the rotation (see PlanningState for further explanation).
max_hash_sizeThe maximal hash size.

Definition at line 32 of file footstep.cpp.

vigir_footstep_planning::Footstep::~Footstep ( )

Definition at line 47 of file footstep.cpp.

Member Function Documentation

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.

Parameters
legThe supporting leg of the possible state.
global_thetaThe (discretized) orientation of the possible state.
xThe (continuous) translation in x direction.
yThe (continuous) translation in y direction.
footstep_xThe resulting (discretized) translation in x direction.
footstep_yThe resulting (discretized) translation in y direction.
Returns
The (discretized) orientation of the resulting state after performing the footstep. This is used to calculate the (discretized) reversed footstep.

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.

Parameters
currentThe planning state representing the robot's current supporting leg.
Returns
The resulting planning state.

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.

Parameters
currentThe planning state representing the robot's current supporting leg.
Returns
The reversed planning state, i.e. the state the robot was in if this footstep had not been performed.

Definition at line 113 of file footstep.cpp.

Member Data Documentation

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.


The documentation for this class was generated from the following files:


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