All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines
Public Member Functions | Private Types | Private Member Functions | Private Attributes
footstep_planner::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>

List of all members.

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 &current) const
 Performs this footstep (translation and rotation) on a given planning state.
PlanningState reverseMeOnThisState (const PlanningState &current) 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 ivCellSize
 The parameter for the discretization of the translation.
std::vector< footstep_xyivDiscPredecessorLeft
 The reversed (discretized) translation(s) for a left supporting foot.
std::vector< footstep_xyivDiscPredecessorRight
 The reversed (discretized) translation(s) for a right supporting foot.
std::vector< footstep_xyivDiscSuccessorLeft
 The (discretized) translation(s) for a left supporting foot.
std::vector< footstep_xyivDiscSuccessorRight
 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.

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 43 of file Footstep.h.


Member Typedef Documentation

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.


Constructor & Destructor Documentation

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.

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.

Definition at line 47 of file Footstep.cpp.


Member Function Documentation

int footstep_planner::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 148 of file Footstep.cpp.

void footstep_planner::Footstep::init ( double  x,
double  y 
) [private]

Initialization method called within the constructor.

Definition at line 52 of file Footstep.cpp.

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 75 of file Footstep.cpp.

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 112 of file Footstep.cpp.


Member Data Documentation

The parameter for the discretization of the translation.

Definition at line 116 of file Footstep.h.

The reversed (discretized) translation(s) for a left supporting foot.

Definition at line 128 of file Footstep.h.

The reversed (discretized) translation(s) for a right supporting foot.

Definition at line 130 of file Footstep.h.

The (discretized) translation(s) for a left supporting foot.

Definition at line 124 of file Footstep.h.

The (discretized) translation(s) for a right supporting foot.

Definition at line 126 of file Footstep.h.

The maximal hash size.

Definition at line 121 of file Footstep.h.

The parameter for the discretization of the rotation.

Definition at line 118 of file Footstep.h.

The (discretized) rotation of the footstep.

Definition at line 113 of file Footstep.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Tue Oct 15 2013 10:06:52