ChppGikLocomotionElement Class Referenceabstract

A locomotion element is a motion planning task that produces threes motion chunks: a 2D Zero Momentum Point motion, a foot motion constraint and a support polygon motion. More...

#include <hpp/gik/motionplanner/element/locomotion-element.hh>

Inheritance diagram for ChppGikLocomotionElement:
Collaboration diagram for ChppGikLocomotionElement:

Public Member Functions

 ChppGikLocomotionElement (ChppGikStandingRobot *inSRobot, double inStartTime, double inDuration, double inSamplingPeriod)
 constructor More...
 
CjrlDynamicRobot * robot ()
 Get a pointer to associated robot. More...
 
virtual ChppGikTransformationConstraintfootConstraintAtTime (double inTime)=0
 Get the foot transformation constraint at given time. More...
 
virtual void preProlongate (double inPreProlongation)
 Mmake this motion constraint return the last planned constraint, from time endTime() to time endTime()+inProlongation. More...
 
virtual void postProlongate (double inPostProlongation)
 Make this motion constraint return the first planned constraint from time current startTime()-inProlongation to current startTime(). More...
 
virtual void startTime (double)
 Disactivated. More...
 
virtual double startTime ()
 Get the start time for this jrlGikMotionConstraint. More...
 
virtual double endTime ()
 Get the end time for this jrlGikMotionConstraint. More...
 
virtual double duration ()
 Get the duration of the original motion. More...
 
virtual CjrlGikMotionConstraintmotionConstraint ()
 Get a pointer to the motion constraint. More...
 
virtual matrixNxPZMPmotion ()
 Get the support foot joint at time inTime. More...
 
virtual CjrlFoot * supportFootAtTime (double inTime)=0
 Get the support foot joint at time inTime. More...
 
virtual bool plan (ChppGikSupportPolygon &supportPolygon, vector3d &ZMP)=0
 Plan stability-consistent ZMP and update given arguments in case of success. More...
 
virtual ~ChppGikLocomotionElement ()
 Destructor. More...
 
- Public Member Functions inherited from CjrlGikMotionConstraint
virtual CjrlGikMotionConstraintclone () const=0
 
virtual CjrlGikStateConstraintstateConstraintAtTime (double inTime)=0
 
virtual ~CjrlGikMotionConstraint ()
 
- Public Member Functions inherited from ChppGikPrioritizedMotion
 ChppGikPrioritizedMotion (CjrlDynamicRobot *inRobot, unsigned int inPriority, CjrlGikMotionConstraint *inMotionConstraint, double inDampingFactor)
 Constructor. More...
 
void workingJoints (const vectorN &inJointsMask)
 Set the joint mask put to work. More...
 
const vectorNworkingJoints () const
 Get the joint mask put to work. More...
 
unsigned int priority () const
 Get the priority. More...
 
double dampingFactor () const
 Get the damping factor. More...
 
CjrlDynamicRobot * robot ()
 Get the robot for this motion. More...
 
virtual ~ChppGikPrioritizedMotion ()
 Destructor. More...
 

Protected Attributes

double attPreProlongation
 
double attPostProlongation
 
double attStartTime
 
double attEndTime
 
double attSamplingPeriod
 
double attEps
 
double attDuration
 
double attModifiedStart
 
double attModifiedEnd
 
CjrlFoot * attSupportFoot
 
CjrlFoot * attConstrainedFoot
 
bool attPlanSuccess
 
matrixNxP attZMPmotion
 
CjrlHumanoidDynamicRobot * attHumanoidRobot
 
ChppGikStandingRobotattStandingRobot
 
- Protected Attributes inherited from ChppGikPrioritizedMotion
CjrlGikMotionConstraintattMotionConstraint
 
vectorN attWorkingJoints
 
unsigned int attPriority
 
CjrlDynamicRobot * attRobot
 
double attDampingFactor
 

Detailed Description

A locomotion element is a motion planning task that produces threes motion chunks: a 2D Zero Momentum Point motion, a foot motion constraint and a support polygon motion.

Constructor & Destructor Documentation

◆ ChppGikLocomotionElement()

ChppGikLocomotionElement::ChppGikLocomotionElement ( ChppGikStandingRobot inSRobot,
double  inStartTime,
double  inDuration,
double  inSamplingPeriod 
)
inline

◆ ~ChppGikLocomotionElement()

virtual ChppGikLocomotionElement::~ChppGikLocomotionElement ( )
inlinevirtual

Destructor.

Member Function Documentation

◆ duration()

virtual double ChppGikLocomotionElement::duration ( )
inlinevirtual

Get the duration of the original motion.

Note
duration of the original motion i.e with prolongation being null

References attDuration.

◆ endTime()

virtual double ChppGikLocomotionElement::endTime ( )
inlinevirtual

Get the end time for this jrlGikMotionConstraint.

Returns
the end time given upon construction plus the postprolongation time

Implements CjrlGikMotionConstraint.

References attModifiedEnd.

◆ footConstraintAtTime()

virtual ChppGikTransformationConstraint* ChppGikLocomotionElement::footConstraintAtTime ( double  inTime)
pure virtual

Get the foot transformation constraint at given time.

Implemented in ChppGikFootDisplaceElement, ChppGikZMPshiftElement, ChppGikStepElement, and ChppGikWalkElement.

Referenced by robot().

◆ motionConstraint()

virtual CjrlGikMotionConstraint* ChppGikLocomotionElement::motionConstraint ( )
inlinevirtual

Get a pointer to the motion constraint.

Reimplemented from ChppGikPrioritizedMotion.

◆ plan()

virtual bool ChppGikLocomotionElement::plan ( ChppGikSupportPolygon supportPolygon,
vector3d ZMP 
)
pure virtual

Plan stability-consistent ZMP and update given arguments in case of success.

Parameters
supportPolygonused and modified by this element according to purpose
ZMPused and modified by this element according to purpose
Returns
false conditions required by implemented planning algorithms not met

Implemented in ChppGikFootDisplaceElement, ChppGikZMPshiftElement, ChppGikStepElement, and ChppGikWalkElement.

Referenced by ZMPmotion().

◆ postProlongate()

virtual void ChppGikLocomotionElement::postProlongate ( double  inPostProlongation)
inlinevirtual

Make this motion constraint return the first planned constraint from time current startTime()-inProlongation to current startTime().

Reimplemented in ChppGikStepElement, and ChppGikWalkElement.

References attEndTime, attModifiedEnd, attPlanSuccess, and attPostProlongation.

◆ preProlongate()

virtual void ChppGikLocomotionElement::preProlongate ( double  inPreProlongation)
inlinevirtual

Mmake this motion constraint return the last planned constraint, from time endTime() to time endTime()+inProlongation.

Reimplemented in ChppGikStepElement, and ChppGikWalkElement.

References attModifiedStart, attPlanSuccess, attPreProlongation, and attStartTime.

◆ robot()

CjrlDynamicRobot* ChppGikLocomotionElement::robot ( )
inlinevirtual

Get a pointer to associated robot.

Implements CjrlGikMotionConstraint.

References ChppGikPrioritizedMotion::attRobot, and footConstraintAtTime().

◆ startTime() [1/2]

virtual void ChppGikLocomotionElement::startTime ( double  )
inlinevirtual

Disactivated.

Implements CjrlGikMotionConstraint.

◆ startTime() [2/2]

virtual double ChppGikLocomotionElement::startTime ( )
inlinevirtual

Get the start time for this jrlGikMotionConstraint.

Returns
the start time given upon construction minus the preprolongation time

Implements CjrlGikMotionConstraint.

References attModifiedStart.

◆ supportFootAtTime()

virtual CjrlFoot* ChppGikLocomotionElement::supportFootAtTime ( double  inTime)
pure virtual

Get the support foot joint at time inTime.

Returns
0 if the time is out of definition bounds

Implemented in ChppGikFootDisplaceElement, ChppGikZMPshiftElement, ChppGikStepElement, and ChppGikWalkElement.

Referenced by ZMPmotion().

◆ ZMPmotion()

virtual matrixNxP& ChppGikLocomotionElement::ZMPmotion ( )
inlinevirtual

Get the support foot joint at time inTime.

Returns
0 if the time is out of definition bounds

References attZMPmotion, plan(), and supportFootAtTime().

Member Data Documentation

◆ attConstrainedFoot

CjrlFoot* ChppGikLocomotionElement::attConstrainedFoot
protected

◆ attDuration

double ChppGikLocomotionElement::attDuration
protected

◆ attEndTime

double ChppGikLocomotionElement::attEndTime
protected

◆ attEps

double ChppGikLocomotionElement::attEps
protected

◆ attHumanoidRobot

CjrlHumanoidDynamicRobot* ChppGikLocomotionElement::attHumanoidRobot
protected

◆ attModifiedEnd

double ChppGikLocomotionElement::attModifiedEnd
protected

◆ attModifiedStart

double ChppGikLocomotionElement::attModifiedStart
protected

◆ attPlanSuccess

bool ChppGikLocomotionElement::attPlanSuccess
protected

◆ attPostProlongation

double ChppGikLocomotionElement::attPostProlongation
protected

◆ attPreProlongation

double ChppGikLocomotionElement::attPreProlongation
protected

◆ attSamplingPeriod

double ChppGikLocomotionElement::attSamplingPeriod
protected

◆ attStandingRobot

ChppGikStandingRobot* ChppGikLocomotionElement::attStandingRobot
protected

◆ attStartTime

double ChppGikLocomotionElement::attStartTime
protected

◆ attSupportFoot

CjrlFoot* ChppGikLocomotionElement::attSupportFoot
protected

◆ attZMPmotion

matrixNxP ChppGikLocomotionElement::attZMPmotion
protected