Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Private Attributes
walk::PatternGenerator< T > Class Template Reference

A pattern generator computes walking reference trajectories. More...

#include <pattern-generator.hh>

List of all members.

Public Types

typedef T concreteType_t
typedef PatternGeneratorTraits
< concreteType_t >::Footprint 
footprint_t
 Footprint type.
typedef PatternGeneratorTraits
< concreteType_t >
::Trajectory2d 
Trajectory2d
 DiscretizedTrajectory in $SO(3)$.
typedef PatternGeneratorTraits
< concreteType_t >
::Trajectory3d 
Trajectory3d
 DiscretizedTrajectory in $SO(3)$.
typedef PatternGeneratorTraits
< concreteType_t >
::TrajectoryNd 
TrajectoryNd
 DiscretizedTrajectory in $R^n$.
typedef PatternGeneratorTraits
< concreteType_t >
::TrajectoryV2d 
TrajectoryV2d
 DiscretizedTrajectory in $R^2$.
typedef PatternGeneratorTraits
< concreteType_t >
::TrajectoryV3d 
TrajectoryV3d
 DiscretizedTrajectory in $R^3$.

Public Member Functions

const footprints_t & footprints () const
 Footprints getter.
PatternGenerator< T > & operator= (const PatternGenerator< T > &)
 Assignment operator.
void setFinalRobotPosition (const HomogeneousMatrix3d &leftFoot, const HomogeneousMatrix3d &rightFoot, const Vector3d &centerOfMass, const Posture &posture)
 Define the final robot state.
void setFinalRobotPosition (const HomogeneousMatrix3d &leftFoot, const HomogeneousMatrix3d &rightFoot, const Vector3d &centerOfMass, const Posture &posture, const HomogeneousMatrix3d &leftHand, const HomogeneousMatrix3d &rightHand)
 Define the final robot state.
void setFootprints (const footprints_t &, bool startWithLeftFoot)
 Set the footprint sequence for the pattern generator.
void setInitialRobotPosition (const HomogeneousMatrix3d &leftFoot, const HomogeneousMatrix3d &rightFoot, const Vector3d &centerOfMass, const Posture &posture)
 Define the initial robot state.
void setInitialRobotPosition (const HomogeneousMatrix3d &leftFoot, const HomogeneousMatrix3d &rightFoot, const Vector3d &centerOfMass, const Posture &posture, const HomogeneousMatrix3d &leftHand, const HomogeneousMatrix3d &rightHand)
 Define the initial robot state.
bool startWithLeftFoot () const
 Is the first flying foot the left one?
typedef WALK_INTERFACES_EIGEN_STL_VECTOR (footprint_t) footprints_t
 Vector of footprints.
Constructor and destructor.
 PatternGenerator ()
 Default constructor.
 PatternGenerator (const PatternGenerator< T > &)
 Copy constructor.
virtual ~PatternGenerator ()
 Destructor.
Trajectories.
const Trajectory3dleftFootTrajectory () const
 Left foot trajectory getter.
const Trajectory3drightFootTrajectory () const
 Right foot trajectory getter.
const TrajectoryV2dzmpTrajectory () const
 ZMP trajectory getter.
const TrajectoryV3dcenterOfMassTrajectory () const
 Center of mass trajectory getter.
const TrajectoryNdpostureTrajectory () const
 Posture trajectory getter.
const Trajectory3dleftHandTrajectory () const
 Left hand trajectory getter.
const Trajectory3drightHandTrajectory () const
 Right hand trajectory getter.
Initial configuration.
const HomogeneousMatrix3dinitialLeftFootPosition () const
 Initial left foot position getter.
const HomogeneousMatrix3dinitialRightFootPosition () const
 Initial right foot position getter.
const Vector3dinitialCenterOfMassPosition () const
 Initial center of mass getter.
const PostureinitialPosture () const
 Initial posture getter.
const HomogeneousMatrix3dinitialLeftHandPosition () const
 Initial left hand position getter.
const HomogeneousMatrix3dinitialRightHandPosition () const
 Initial right hand position getter.
Final configuration
const HomogeneousMatrix3dfinalLeftFootPosition () const
 Final left foot position getter.
const HomogeneousMatrix3dfinalRightFootPosition () const
 Final right foot position getter.
const Vector3dfinalCenterOfMassPosition () const
 Final center of mass position getter.
const PosturefinalPosture () const
 Final posture getter.
const HomogeneousMatrix3dfinalLeftHandPosition () const
 Final left hand position getter.
const HomogeneousMatrix3dfinalRightHandPosition () const
 Final right hand position getter.

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Protected Member Functions

virtual void computeTrajectories ()=0
 Compute the reference trajectories.
TrajectoryV3dgetCenterOfMassTrajectory ()
 Center of mass trajectory setter.
Vector3dgetFinalCenterOfMassPosition ()
 Final center of mass position setter.
HomogeneousMatrix3dgetFinalLeftFootPosition ()
 Final left foot position setter.
HomogeneousMatrix3dgetFinalLeftHandPosition ()
 Final left hand position setter.
PosturegetFinalPosture ()
 Final posture setter.
HomogeneousMatrix3dgetFinalRightFootPosition ()
 Final right foot position setter.
HomogeneousMatrix3dgetFinalRightHandPosition ()
 Final right hand position setter.
Vector3dgetInitialCenterOfMassPosition ()
 Initial center of mass position setter.
HomogeneousMatrix3dgetInitialLeftFootPosition ()
 Initial left foot position setter.
HomogeneousMatrix3dgetInitialLeftHandPosition ()
 Initial left hand position setter.
PosturegetInitialPosture ()
 Initial posture setter.
HomogeneousMatrix3dgetInitialRightFootPosition ()
 Initial right foot position setter.
HomogeneousMatrix3dgetInitialRightHandPosition ()
 Initial right hand position setter.
Trajectory3dgetLeftFootTrajectory ()
 Left foot trajectory setter.
Trajectory3dgetLeftHandTrajectory ()
 Left hand trajectory setter.
TrajectoryNdgetPostureTrajectory ()
 Posture trajectory setter.
Trajectory3dgetRightFootTrajectory ()
 Right foot trajectory setter.
Trajectory3dgetRightHandTrajectory ()
 Right hand trajectory setter.
TrajectoryV2dgetZmpTrajectory ()
 ZMP trajectory setter.

Private Attributes

TrajectoryV3d centerOfMassTrajectory_
 Center of mass trajectory.
Vector3d finalCenterOfMassPosition_
 Final center of mass position.
HomogeneousMatrix3d finalLeftFootPosition_
 Final left foot position.
HomogeneousMatrix3d finalLeftHandPosition_
 Final left hand position.
Posture finalPosture_
 Final posture.
HomogeneousMatrix3d finalRightFootPosition_
 Final right foot position.
HomogeneousMatrix3d finalRightHandPosition_
 Final right hand position.
footprints_t footprints_
 Footprint sequence.
Vector3d initialCenterOfMassPosition_
 Initial center of mass position.
HomogeneousMatrix3d initialLeftFootPosition_
 Initial left foot position.
HomogeneousMatrix3d initialLeftHandPosition_
 Initial left hand position.
Posture initialPosture_
 Initial posture.
HomogeneousMatrix3d initialRightFootPosition_
 Initial right foot position.
HomogeneousMatrix3d initialRightHandPosition_
 Initial right hand position.
Trajectory3d leftFootTrajectory_
 Left foot trajectory.
Trajectory3d leftHandTrajectory_
 Left hand trajectory.
TrajectoryNd postureTrajectory_
 Posture trajectory.
Trajectory3d rightFootTrajectory_
 Right foot trajectory.
Trajectory3d rightHandTrajectory_
 Right hand trajectory.
bool startWithLeftFoot_
 Is the left foot the first flying foot?
TrajectoryV2d zmpTrajectory_
 ZMP trajectory.

Detailed Description

template<typename T>
class walk::PatternGenerator< T >

A pattern generator computes walking reference trajectories.

This class is the core of walk_interfaces. A pattern generator computes the reference trajectories of associated with a given walking movement.

The frames follows the ROS conventions (X forward, Y left and Z up).

The reference trajectories are:

Template Parameters:
TPattern generator concrete type.

Definition at line 51 of file pattern-generator.hh.


Member Typedef Documentation

template<typename T>
typedef T walk::PatternGenerator< T >::concreteType_t

Definition at line 54 of file pattern-generator.hh.

template<typename T>
typedef PatternGeneratorTraits<concreteType_t>::Footprint walk::PatternGenerator< T >::footprint_t

Footprint type.

Definition at line 58 of file pattern-generator.hh.

DiscretizedTrajectory in $SO(3)$.

Definition at line 65 of file pattern-generator.hh.

DiscretizedTrajectory in $SO(3)$.

Definition at line 62 of file pattern-generator.hh.

DiscretizedTrajectory in $R^n$.

Definition at line 74 of file pattern-generator.hh.

DiscretizedTrajectory in $R^2$.

Definition at line 68 of file pattern-generator.hh.

DiscretizedTrajectory in $R^3$.

Definition at line 71 of file pattern-generator.hh.


Constructor & Destructor Documentation

template<typename T>
walk::PatternGenerator< T >::PatternGenerator ( ) [explicit]

Default constructor.

template<typename T>
walk::PatternGenerator< T >::PatternGenerator ( const PatternGenerator< T > &  ) [explicit]

Copy constructor.

template<typename T>
virtual walk::PatternGenerator< T >::~PatternGenerator ( ) [virtual]

Destructor.


Member Function Documentation

template<typename T>
const TrajectoryV3d& walk::PatternGenerator< T >::centerOfMassTrajectory ( ) const

Center of mass trajectory getter.

template<typename T>
virtual void walk::PatternGenerator< T >::computeTrajectories ( ) [protected, pure virtual]

Compute the reference trajectories.

This abstract virtual method must be defined in the child classes. It must compute the reference trajectories and fill the different attributes of this class using the protected setters.

Implemented in MyPatternGenerator.

template<typename T>
const Vector3d& walk::PatternGenerator< T >::finalCenterOfMassPosition ( ) const

Final center of mass position getter.

template<typename T>
const HomogeneousMatrix3d& walk::PatternGenerator< T >::finalLeftFootPosition ( ) const

Final left foot position getter.

template<typename T>
const HomogeneousMatrix3d& walk::PatternGenerator< T >::finalLeftHandPosition ( ) const

Final left hand position getter.

template<typename T>
const Posture& walk::PatternGenerator< T >::finalPosture ( ) const

Final posture getter.

template<typename T>
const HomogeneousMatrix3d& walk::PatternGenerator< T >::finalRightFootPosition ( ) const

Final right foot position getter.

template<typename T>
const HomogeneousMatrix3d& walk::PatternGenerator< T >::finalRightHandPosition ( ) const

Final right hand position getter.

template<typename T>
const footprints_t& walk::PatternGenerator< T >::footprints ( ) const

Footprints getter.

template<typename T>
TrajectoryV3d& walk::PatternGenerator< T >::getCenterOfMassTrajectory ( ) [protected]

Center of mass trajectory setter.

template<typename T>
Vector3d& walk::PatternGenerator< T >::getFinalCenterOfMassPosition ( ) [protected]

Final center of mass position setter.

template<typename T>
HomogeneousMatrix3d& walk::PatternGenerator< T >::getFinalLeftFootPosition ( ) [protected]

Final left foot position setter.

template<typename T>
HomogeneousMatrix3d& walk::PatternGenerator< T >::getFinalLeftHandPosition ( ) [protected]

Final left hand position setter.

template<typename T>
Posture& walk::PatternGenerator< T >::getFinalPosture ( ) [protected]

Final posture setter.

template<typename T>
HomogeneousMatrix3d& walk::PatternGenerator< T >::getFinalRightFootPosition ( ) [protected]

Final right foot position setter.

template<typename T>
HomogeneousMatrix3d& walk::PatternGenerator< T >::getFinalRightHandPosition ( ) [protected]

Final right hand position setter.

template<typename T>
Vector3d& walk::PatternGenerator< T >::getInitialCenterOfMassPosition ( ) [protected]

Initial center of mass position setter.

template<typename T>
HomogeneousMatrix3d& walk::PatternGenerator< T >::getInitialLeftFootPosition ( ) [protected]

Initial left foot position setter.

template<typename T>
HomogeneousMatrix3d& walk::PatternGenerator< T >::getInitialLeftHandPosition ( ) [protected]

Initial left hand position setter.

template<typename T>
Posture& walk::PatternGenerator< T >::getInitialPosture ( ) [protected]

Initial posture setter.

template<typename T>
HomogeneousMatrix3d& walk::PatternGenerator< T >::getInitialRightFootPosition ( ) [protected]

Initial right foot position setter.

template<typename T>
HomogeneousMatrix3d& walk::PatternGenerator< T >::getInitialRightHandPosition ( ) [protected]

Initial right hand position setter.

template<typename T>
Trajectory3d& walk::PatternGenerator< T >::getLeftFootTrajectory ( ) [protected]

Left foot trajectory setter.

template<typename T>
Trajectory3d& walk::PatternGenerator< T >::getLeftHandTrajectory ( ) [protected]

Left hand trajectory setter.

template<typename T>
TrajectoryNd& walk::PatternGenerator< T >::getPostureTrajectory ( ) [protected]

Posture trajectory setter.

template<typename T>
Trajectory3d& walk::PatternGenerator< T >::getRightFootTrajectory ( ) [protected]

Right foot trajectory setter.

template<typename T>
Trajectory3d& walk::PatternGenerator< T >::getRightHandTrajectory ( ) [protected]

Right hand trajectory setter.

template<typename T>
TrajectoryV2d& walk::PatternGenerator< T >::getZmpTrajectory ( ) [protected]

ZMP trajectory setter.

template<typename T>
const Vector3d& walk::PatternGenerator< T >::initialCenterOfMassPosition ( ) const

Initial center of mass getter.

template<typename T>
const HomogeneousMatrix3d& walk::PatternGenerator< T >::initialLeftFootPosition ( ) const

Initial left foot position getter.

template<typename T>
const HomogeneousMatrix3d& walk::PatternGenerator< T >::initialLeftHandPosition ( ) const

Initial left hand position getter.

template<typename T>
const Posture& walk::PatternGenerator< T >::initialPosture ( ) const

Initial posture getter.

template<typename T>
const HomogeneousMatrix3d& walk::PatternGenerator< T >::initialRightFootPosition ( ) const

Initial right foot position getter.

template<typename T>
const HomogeneousMatrix3d& walk::PatternGenerator< T >::initialRightHandPosition ( ) const

Initial right hand position getter.

template<typename T>
const Trajectory3d& walk::PatternGenerator< T >::leftFootTrajectory ( ) const

Left foot trajectory getter.

template<typename T>
const Trajectory3d& walk::PatternGenerator< T >::leftHandTrajectory ( ) const

Left hand trajectory getter.

template<typename T>
PatternGenerator<T>& walk::PatternGenerator< T >::operator= ( const PatternGenerator< T > &  )

Assignment operator.

template<typename T>
const TrajectoryNd& walk::PatternGenerator< T >::postureTrajectory ( ) const

Posture trajectory getter.

template<typename T>
const Trajectory3d& walk::PatternGenerator< T >::rightFootTrajectory ( ) const

Right foot trajectory getter.

template<typename T>
const Trajectory3d& walk::PatternGenerator< T >::rightHandTrajectory ( ) const

Right hand trajectory getter.

template<typename T>
void walk::PatternGenerator< T >::setFinalRobotPosition ( const HomogeneousMatrix3d leftFoot,
const HomogeneousMatrix3d rightFoot,
const Vector3d centerOfMass,
const Posture posture 
)

Define the final robot state.

Parameters:
leftFootleft foot final position.
rightFootright foot final position.
centerOfMasscenter of mass final position.
posturefinal posture.
template<typename T>
void walk::PatternGenerator< T >::setFinalRobotPosition ( const HomogeneousMatrix3d leftFoot,
const HomogeneousMatrix3d rightFoot,
const Vector3d centerOfMass,
const Posture posture,
const HomogeneousMatrix3d leftHand,
const HomogeneousMatrix3d rightHand 
)

Define the final robot state.

Parameters:
leftFootleft foot final position.
rightFootright foot final position.
centerOfMasscenter of mass final position.
posturefinal posture.
leftHandleft hand final position.
rightHandright hand final position.
template<typename T>
void walk::PatternGenerator< T >::setFootprints ( const footprints_t &  ,
bool  startWithLeftFoot 
)

Set the footprint sequence for the pattern generator.

Parameters:
startWithLeftFootTrue if the movement first flying foot is the left foot, false otherwise. It is then assumed that the footprints alternate between left and right.
template<typename T>
void walk::PatternGenerator< T >::setInitialRobotPosition ( const HomogeneousMatrix3d leftFoot,
const HomogeneousMatrix3d rightFoot,
const Vector3d centerOfMass,
const Posture posture 
)

Define the initial robot state.

Parameters:
leftFootleft foot initial position.
rightFootright foot initial position.
centerOfMasscenter of mass initial position.
postureinitial posture.
template<typename T>
void walk::PatternGenerator< T >::setInitialRobotPosition ( const HomogeneousMatrix3d leftFoot,
const HomogeneousMatrix3d rightFoot,
const Vector3d centerOfMass,
const Posture posture,
const HomogeneousMatrix3d leftHand,
const HomogeneousMatrix3d rightHand 
)

Define the initial robot state.

Parameters:
leftFootleft foot initial position.
rightFootright foot initial position.
centerOfMasscenter of mass initial position.
postureinitial posture.
leftHandleft hand initial position.
rightHandright hand initial position.
template<typename T>
bool walk::PatternGenerator< T >::startWithLeftFoot ( ) const

Is the first flying foot the left one?

template<typename T>
typedef walk::PatternGenerator< T >::WALK_INTERFACES_EIGEN_STL_VECTOR ( footprint_t  )

Vector of footprints.

template<typename T>
const TrajectoryV2d& walk::PatternGenerator< T >::zmpTrajectory ( ) const

ZMP trajectory getter.


Member Data Documentation

template<typename T>
TrajectoryV3d walk::PatternGenerator< T >::centerOfMassTrajectory_ [private]

Center of mass trajectory.

Definition at line 280 of file pattern-generator.hh.

Definition at line 317 of file pattern-generator.hh.

template<typename T>
Vector3d walk::PatternGenerator< T >::finalCenterOfMassPosition_ [private]

Final center of mass position.

Definition at line 309 of file pattern-generator.hh.

Final left foot position.

Definition at line 305 of file pattern-generator.hh.

Final left hand position.

Definition at line 313 of file pattern-generator.hh.

template<typename T>
Posture walk::PatternGenerator< T >::finalPosture_ [private]

Final posture.

Definition at line 311 of file pattern-generator.hh.

Final right foot position.

Definition at line 307 of file pattern-generator.hh.

Final right hand position.

Definition at line 315 of file pattern-generator.hh.

template<typename T>
footprints_t walk::PatternGenerator< T >::footprints_ [private]

Footprint sequence.

Definition at line 272 of file pattern-generator.hh.

template<typename T>
Vector3d walk::PatternGenerator< T >::initialCenterOfMassPosition_ [private]

Initial center of mass position.

Definition at line 296 of file pattern-generator.hh.

Initial left foot position.

Definition at line 292 of file pattern-generator.hh.

Initial left hand position.

Definition at line 300 of file pattern-generator.hh.

template<typename T>
Posture walk::PatternGenerator< T >::initialPosture_ [private]

Initial posture.

Definition at line 298 of file pattern-generator.hh.

Initial right foot position.

Definition at line 294 of file pattern-generator.hh.

Initial right hand position.

Definition at line 302 of file pattern-generator.hh.

template<typename T>
Trajectory3d walk::PatternGenerator< T >::leftFootTrajectory_ [private]

Left foot trajectory.

Definition at line 276 of file pattern-generator.hh.

template<typename T>
Trajectory3d walk::PatternGenerator< T >::leftHandTrajectory_ [private]

Left hand trajectory.

Definition at line 286 of file pattern-generator.hh.

template<typename T>
TrajectoryNd walk::PatternGenerator< T >::postureTrajectory_ [private]

Posture trajectory.

Definition at line 284 of file pattern-generator.hh.

template<typename T>
Trajectory3d walk::PatternGenerator< T >::rightFootTrajectory_ [private]

Right foot trajectory.

Definition at line 278 of file pattern-generator.hh.

template<typename T>
Trajectory3d walk::PatternGenerator< T >::rightHandTrajectory_ [private]

Right hand trajectory.

Definition at line 288 of file pattern-generator.hh.

template<typename T>
bool walk::PatternGenerator< T >::startWithLeftFoot_ [private]

Is the left foot the first flying foot?

Definition at line 274 of file pattern-generator.hh.

template<typename T>
TrajectoryV2d walk::PatternGenerator< T >::zmpTrajectory_ [private]

ZMP trajectory.

Definition at line 282 of file pattern-generator.hh.


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


walk_interfaces
Author(s): Thomas Moulard/thomas.moulard@gmail.com, Antonio El Khoury
autogenerated on Sat Dec 28 2013 17:05:21