A pattern generator computes walking reference trajectories. More...
#include <pattern-generator.hh>
Public Types | |
typedef T | concreteType_t |
typedef PatternGeneratorTraits < concreteType_t >::Footprint | footprint_t |
Footprint type. | |
typedef PatternGeneratorTraits < concreteType_t > ::Trajectory2d | Trajectory2d |
DiscretizedTrajectory in . | |
typedef PatternGeneratorTraits < concreteType_t > ::Trajectory3d | Trajectory3d |
DiscretizedTrajectory in . | |
typedef PatternGeneratorTraits < concreteType_t > ::TrajectoryNd | TrajectoryNd |
DiscretizedTrajectory in . | |
typedef PatternGeneratorTraits < concreteType_t > ::TrajectoryV2d | TrajectoryV2d |
DiscretizedTrajectory in . | |
typedef PatternGeneratorTraits < concreteType_t > ::TrajectoryV3d | TrajectoryV3d |
DiscretizedTrajectory in . | |
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 ¢erOfMass, const Posture &posture) |
Define the final robot state. | |
void | setFinalRobotPosition (const HomogeneousMatrix3d &leftFoot, const HomogeneousMatrix3d &rightFoot, const Vector3d ¢erOfMass, 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 ¢erOfMass, const Posture &posture) |
Define the initial robot state. | |
void | setInitialRobotPosition (const HomogeneousMatrix3d &leftFoot, const HomogeneousMatrix3d &rightFoot, const Vector3d ¢erOfMass, 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 Trajectory3d & | leftFootTrajectory () const |
Left foot trajectory getter. | |
const Trajectory3d & | rightFootTrajectory () const |
Right foot trajectory getter. | |
const TrajectoryV2d & | zmpTrajectory () const |
ZMP trajectory getter. | |
const TrajectoryV3d & | centerOfMassTrajectory () const |
Center of mass trajectory getter. | |
const TrajectoryNd & | postureTrajectory () const |
Posture trajectory getter. | |
const Trajectory3d & | leftHandTrajectory () const |
Left hand trajectory getter. | |
const Trajectory3d & | rightHandTrajectory () const |
Right hand trajectory getter. | |
Initial configuration. | |
const HomogeneousMatrix3d & | initialLeftFootPosition () const |
Initial left foot position getter. | |
const HomogeneousMatrix3d & | initialRightFootPosition () const |
Initial right foot position getter. | |
const Vector3d & | initialCenterOfMassPosition () const |
Initial center of mass getter. | |
const Posture & | initialPosture () const |
Initial posture getter. | |
const HomogeneousMatrix3d & | initialLeftHandPosition () const |
Initial left hand position getter. | |
const HomogeneousMatrix3d & | initialRightHandPosition () const |
Initial right hand position getter. | |
Final configuration | |
const HomogeneousMatrix3d & | finalLeftFootPosition () const |
Final left foot position getter. | |
const HomogeneousMatrix3d & | finalRightFootPosition () const |
Final right foot position getter. | |
const Vector3d & | finalCenterOfMassPosition () const |
Final center of mass position getter. | |
const Posture & | finalPosture () const |
Final posture getter. | |
const HomogeneousMatrix3d & | finalLeftHandPosition () const |
Final left hand position getter. | |
const HomogeneousMatrix3d & | finalRightHandPosition () const |
Final right hand position getter. | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | |
Protected Member Functions | |
virtual void | computeTrajectories ()=0 |
Compute the reference trajectories. | |
TrajectoryV3d & | getCenterOfMassTrajectory () |
Center of mass trajectory setter. | |
Vector3d & | getFinalCenterOfMassPosition () |
Final center of mass position setter. | |
HomogeneousMatrix3d & | getFinalLeftFootPosition () |
Final left foot position setter. | |
HomogeneousMatrix3d & | getFinalLeftHandPosition () |
Final left hand position setter. | |
Posture & | getFinalPosture () |
Final posture setter. | |
HomogeneousMatrix3d & | getFinalRightFootPosition () |
Final right foot position setter. | |
HomogeneousMatrix3d & | getFinalRightHandPosition () |
Final right hand position setter. | |
Vector3d & | getInitialCenterOfMassPosition () |
Initial center of mass position setter. | |
HomogeneousMatrix3d & | getInitialLeftFootPosition () |
Initial left foot position setter. | |
HomogeneousMatrix3d & | getInitialLeftHandPosition () |
Initial left hand position setter. | |
Posture & | getInitialPosture () |
Initial posture setter. | |
HomogeneousMatrix3d & | getInitialRightFootPosition () |
Initial right foot position setter. | |
HomogeneousMatrix3d & | getInitialRightHandPosition () |
Initial right hand position setter. | |
Trajectory3d & | getLeftFootTrajectory () |
Left foot trajectory setter. | |
Trajectory3d & | getLeftHandTrajectory () |
Left hand trajectory setter. | |
TrajectoryNd & | getPostureTrajectory () |
Posture trajectory setter. | |
Trajectory3d & | getRightFootTrajectory () |
Right foot trajectory setter. | |
Trajectory3d & | getRightHandTrajectory () |
Right hand trajectory setter. | |
TrajectoryV2d & | getZmpTrajectory () |
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. |
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:
T | Pattern generator concrete type. |
Definition at line 51 of file pattern-generator.hh.
typedef T walk::PatternGenerator< T >::concreteType_t |
Definition at line 54 of file pattern-generator.hh.
typedef PatternGeneratorTraits<concreteType_t>::Footprint walk::PatternGenerator< T >::footprint_t |
Footprint type.
Definition at line 58 of file pattern-generator.hh.
typedef PatternGeneratorTraits<concreteType_t>::Trajectory2d walk::PatternGenerator< T >::Trajectory2d |
Definition at line 65 of file pattern-generator.hh.
typedef PatternGeneratorTraits<concreteType_t>::Trajectory3d walk::PatternGenerator< T >::Trajectory3d |
Definition at line 62 of file pattern-generator.hh.
typedef PatternGeneratorTraits<concreteType_t>::TrajectoryNd walk::PatternGenerator< T >::TrajectoryNd |
Definition at line 74 of file pattern-generator.hh.
typedef PatternGeneratorTraits<concreteType_t>::TrajectoryV2d walk::PatternGenerator< T >::TrajectoryV2d |
Definition at line 68 of file pattern-generator.hh.
typedef PatternGeneratorTraits<concreteType_t>::TrajectoryV3d walk::PatternGenerator< T >::TrajectoryV3d |
Definition at line 71 of file pattern-generator.hh.
walk::PatternGenerator< T >::PatternGenerator | ( | ) | [explicit] |
Default constructor.
walk::PatternGenerator< T >::PatternGenerator | ( | const PatternGenerator< T > & | ) | [explicit] |
Copy constructor.
virtual walk::PatternGenerator< T >::~PatternGenerator | ( | ) | [virtual] |
Destructor.
const TrajectoryV3d& walk::PatternGenerator< T >::centerOfMassTrajectory | ( | ) | const |
Center of mass trajectory getter.
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.
const Vector3d& walk::PatternGenerator< T >::finalCenterOfMassPosition | ( | ) | const |
Final center of mass position getter.
const HomogeneousMatrix3d& walk::PatternGenerator< T >::finalLeftFootPosition | ( | ) | const |
Final left foot position getter.
const HomogeneousMatrix3d& walk::PatternGenerator< T >::finalLeftHandPosition | ( | ) | const |
Final left hand position getter.
const Posture& walk::PatternGenerator< T >::finalPosture | ( | ) | const |
Final posture getter.
const HomogeneousMatrix3d& walk::PatternGenerator< T >::finalRightFootPosition | ( | ) | const |
Final right foot position getter.
const HomogeneousMatrix3d& walk::PatternGenerator< T >::finalRightHandPosition | ( | ) | const |
Final right hand position getter.
const footprints_t& walk::PatternGenerator< T >::footprints | ( | ) | const |
Footprints getter.
TrajectoryV3d& walk::PatternGenerator< T >::getCenterOfMassTrajectory | ( | ) | [protected] |
Center of mass trajectory setter.
Vector3d& walk::PatternGenerator< T >::getFinalCenterOfMassPosition | ( | ) | [protected] |
Final center of mass position setter.
HomogeneousMatrix3d& walk::PatternGenerator< T >::getFinalLeftFootPosition | ( | ) | [protected] |
Final left foot position setter.
HomogeneousMatrix3d& walk::PatternGenerator< T >::getFinalLeftHandPosition | ( | ) | [protected] |
Final left hand position setter.
Posture& walk::PatternGenerator< T >::getFinalPosture | ( | ) | [protected] |
Final posture setter.
HomogeneousMatrix3d& walk::PatternGenerator< T >::getFinalRightFootPosition | ( | ) | [protected] |
Final right foot position setter.
HomogeneousMatrix3d& walk::PatternGenerator< T >::getFinalRightHandPosition | ( | ) | [protected] |
Final right hand position setter.
Vector3d& walk::PatternGenerator< T >::getInitialCenterOfMassPosition | ( | ) | [protected] |
Initial center of mass position setter.
HomogeneousMatrix3d& walk::PatternGenerator< T >::getInitialLeftFootPosition | ( | ) | [protected] |
Initial left foot position setter.
HomogeneousMatrix3d& walk::PatternGenerator< T >::getInitialLeftHandPosition | ( | ) | [protected] |
Initial left hand position setter.
Posture& walk::PatternGenerator< T >::getInitialPosture | ( | ) | [protected] |
Initial posture setter.
HomogeneousMatrix3d& walk::PatternGenerator< T >::getInitialRightFootPosition | ( | ) | [protected] |
Initial right foot position setter.
HomogeneousMatrix3d& walk::PatternGenerator< T >::getInitialRightHandPosition | ( | ) | [protected] |
Initial right hand position setter.
Trajectory3d& walk::PatternGenerator< T >::getLeftFootTrajectory | ( | ) | [protected] |
Left foot trajectory setter.
Trajectory3d& walk::PatternGenerator< T >::getLeftHandTrajectory | ( | ) | [protected] |
Left hand trajectory setter.
TrajectoryNd& walk::PatternGenerator< T >::getPostureTrajectory | ( | ) | [protected] |
Posture trajectory setter.
Trajectory3d& walk::PatternGenerator< T >::getRightFootTrajectory | ( | ) | [protected] |
Right foot trajectory setter.
Trajectory3d& walk::PatternGenerator< T >::getRightHandTrajectory | ( | ) | [protected] |
Right hand trajectory setter.
TrajectoryV2d& walk::PatternGenerator< T >::getZmpTrajectory | ( | ) | [protected] |
ZMP trajectory setter.
const Vector3d& walk::PatternGenerator< T >::initialCenterOfMassPosition | ( | ) | const |
Initial center of mass getter.
const HomogeneousMatrix3d& walk::PatternGenerator< T >::initialLeftFootPosition | ( | ) | const |
Initial left foot position getter.
const HomogeneousMatrix3d& walk::PatternGenerator< T >::initialLeftHandPosition | ( | ) | const |
Initial left hand position getter.
const Posture& walk::PatternGenerator< T >::initialPosture | ( | ) | const |
Initial posture getter.
const HomogeneousMatrix3d& walk::PatternGenerator< T >::initialRightFootPosition | ( | ) | const |
Initial right foot position getter.
const HomogeneousMatrix3d& walk::PatternGenerator< T >::initialRightHandPosition | ( | ) | const |
Initial right hand position getter.
const Trajectory3d& walk::PatternGenerator< T >::leftFootTrajectory | ( | ) | const |
Left foot trajectory getter.
const Trajectory3d& walk::PatternGenerator< T >::leftHandTrajectory | ( | ) | const |
Left hand trajectory getter.
PatternGenerator<T>& walk::PatternGenerator< T >::operator= | ( | const PatternGenerator< T > & | ) |
Assignment operator.
const TrajectoryNd& walk::PatternGenerator< T >::postureTrajectory | ( | ) | const |
Posture trajectory getter.
const Trajectory3d& walk::PatternGenerator< T >::rightFootTrajectory | ( | ) | const |
Right foot trajectory getter.
const Trajectory3d& walk::PatternGenerator< T >::rightHandTrajectory | ( | ) | const |
Right hand trajectory getter.
void walk::PatternGenerator< T >::setFinalRobotPosition | ( | const HomogeneousMatrix3d & | leftFoot, |
const HomogeneousMatrix3d & | rightFoot, | ||
const Vector3d & | centerOfMass, | ||
const Posture & | posture | ||
) |
Define the final robot state.
leftFoot | left foot final position. |
rightFoot | right foot final position. |
centerOfMass | center of mass final position. |
posture | final posture. |
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.
leftFoot | left foot final position. |
rightFoot | right foot final position. |
centerOfMass | center of mass final position. |
posture | final posture. |
leftHand | left hand final position. |
rightHand | right hand final position. |
void walk::PatternGenerator< T >::setFootprints | ( | const footprints_t & | , |
bool | startWithLeftFoot | ||
) |
Set the footprint sequence for the pattern generator.
startWithLeftFoot | True if the movement first flying foot is the left foot, false otherwise. It is then assumed that the footprints alternate between left and right. |
void walk::PatternGenerator< T >::setInitialRobotPosition | ( | const HomogeneousMatrix3d & | leftFoot, |
const HomogeneousMatrix3d & | rightFoot, | ||
const Vector3d & | centerOfMass, | ||
const Posture & | posture | ||
) |
Define the initial robot state.
leftFoot | left foot initial position. |
rightFoot | right foot initial position. |
centerOfMass | center of mass initial position. |
posture | initial posture. |
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.
leftFoot | left foot initial position. |
rightFoot | right foot initial position. |
centerOfMass | center of mass initial position. |
posture | initial posture. |
leftHand | left hand initial position. |
rightHand | right hand initial position. |
bool walk::PatternGenerator< T >::startWithLeftFoot | ( | ) | const |
Is the first flying foot the left one?
typedef walk::PatternGenerator< T >::WALK_INTERFACES_EIGEN_STL_VECTOR | ( | footprint_t | ) |
Vector of footprints.
const TrajectoryV2d& walk::PatternGenerator< T >::zmpTrajectory | ( | ) | const |
ZMP trajectory getter.
TrajectoryV3d walk::PatternGenerator< T >::centerOfMassTrajectory_ [private] |
Center of mass trajectory.
Definition at line 280 of file pattern-generator.hh.
walk::PatternGenerator< T >::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
Definition at line 317 of file pattern-generator.hh.
Vector3d walk::PatternGenerator< T >::finalCenterOfMassPosition_ [private] |
Final center of mass position.
Definition at line 309 of file pattern-generator.hh.
HomogeneousMatrix3d walk::PatternGenerator< T >::finalLeftFootPosition_ [private] |
Final left foot position.
Definition at line 305 of file pattern-generator.hh.
HomogeneousMatrix3d walk::PatternGenerator< T >::finalLeftHandPosition_ [private] |
Final left hand position.
Definition at line 313 of file pattern-generator.hh.
Posture walk::PatternGenerator< T >::finalPosture_ [private] |
Final posture.
Definition at line 311 of file pattern-generator.hh.
HomogeneousMatrix3d walk::PatternGenerator< T >::finalRightFootPosition_ [private] |
Final right foot position.
Definition at line 307 of file pattern-generator.hh.
HomogeneousMatrix3d walk::PatternGenerator< T >::finalRightHandPosition_ [private] |
Final right hand position.
Definition at line 315 of file pattern-generator.hh.
footprints_t walk::PatternGenerator< T >::footprints_ [private] |
Footprint sequence.
Definition at line 272 of file pattern-generator.hh.
Vector3d walk::PatternGenerator< T >::initialCenterOfMassPosition_ [private] |
Initial center of mass position.
Definition at line 296 of file pattern-generator.hh.
HomogeneousMatrix3d walk::PatternGenerator< T >::initialLeftFootPosition_ [private] |
Initial left foot position.
Definition at line 292 of file pattern-generator.hh.
HomogeneousMatrix3d walk::PatternGenerator< T >::initialLeftHandPosition_ [private] |
Initial left hand position.
Definition at line 300 of file pattern-generator.hh.
Posture walk::PatternGenerator< T >::initialPosture_ [private] |
Initial posture.
Definition at line 298 of file pattern-generator.hh.
HomogeneousMatrix3d walk::PatternGenerator< T >::initialRightFootPosition_ [private] |
Initial right foot position.
Definition at line 294 of file pattern-generator.hh.
HomogeneousMatrix3d walk::PatternGenerator< T >::initialRightHandPosition_ [private] |
Initial right hand position.
Definition at line 302 of file pattern-generator.hh.
Trajectory3d walk::PatternGenerator< T >::leftFootTrajectory_ [private] |
Left foot trajectory.
Definition at line 276 of file pattern-generator.hh.
Trajectory3d walk::PatternGenerator< T >::leftHandTrajectory_ [private] |
Left hand trajectory.
Definition at line 286 of file pattern-generator.hh.
TrajectoryNd walk::PatternGenerator< T >::postureTrajectory_ [private] |
Posture trajectory.
Definition at line 284 of file pattern-generator.hh.
Trajectory3d walk::PatternGenerator< T >::rightFootTrajectory_ [private] |
Right foot trajectory.
Definition at line 278 of file pattern-generator.hh.
Trajectory3d walk::PatternGenerator< T >::rightHandTrajectory_ [private] |
Right hand trajectory.
Definition at line 288 of file pattern-generator.hh.
bool walk::PatternGenerator< T >::startWithLeftFoot_ [private] |
Is the left foot the first flying foot?
Definition at line 274 of file pattern-generator.hh.
TrajectoryV2d walk::PatternGenerator< T >::zmpTrajectory_ [private] |
ZMP trajectory.
Definition at line 282 of file pattern-generator.hh.