ChppGikLocomotionPlan Class Reference

This is a locomotion plan for objects of type ChppGikLocomotionElement. More...

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

Public Member Functions

 ~ChppGikLocomotionPlan ()
 Destructor. More...
 
Construction

{@

 ChppGikLocomotionPlan (ChppGikMotionPlan *inAssociatedMotionPlan, ChppGikStandingRobot *inStandingRobot, double inSamplingPeriod)
 Constructor. More...
 
bool addElement (ChppGikLocomotionElement *inElement)
 Add a locomotion element (the object is not copied). More...
 
void clearElements ()
 Delete entered elements (the object deleted) More...
 
double endTime ()
 Get the end time according to entered elements. More...
 
double startTime ()
 Get the start time according to entered elements. More...
 
double extraEndTime ()
 Get an extra end time. More...
 
void extraEndTime (double inDuration)
 Set an extra end time. More...
 
Computations

{@

bool solve ()
 Solve = based on the entered elements do: More...
 
bool getWeightsAtTime (double inTime, vectorN &outWeights)
 Get an appropriate joints weighting vecotr according to current task. More...
 
bool getZMPAtTime (double inTime, vectorN &outZMP)
 Get planned ZMP at time inTime. More...
 
const ChppGikLocomotionElementactiveElement (double inTime) const
 Get the currently active task if any. More...
 
CjrlJoint * supportFootJoint (double inTime)
 Get the default support foot joint at the given time. More...
 
ChppGikLocomotionDatadataAtTime (double inTime)
 Get all locomotion data at given time. More...
 
bool filterZMP (matrixNxP &zmpError)
 filter ZMP trajectory. More...
 

Detailed Description

This is a locomotion plan for objects of type ChppGikLocomotionElement.

its purpose is to transform ChppGikLocomotionElement objects into ChppGikPrioritizedMotion objects which can be inserted in a ChppGikMotionPlan object

Constructor & Destructor Documentation

◆ ChppGikLocomotionPlan()

ChppGikLocomotionPlan::ChppGikLocomotionPlan ( ChppGikMotionPlan inAssociatedMotionPlan,
ChppGikStandingRobot inStandingRobot,
double  inSamplingPeriod 
)

Constructor.

Note
the start time is fixed to 0.0

◆ ~ChppGikLocomotionPlan()

ChppGikLocomotionPlan::~ChppGikLocomotionPlan ( )

Destructor.

Member Function Documentation

◆ activeElement()

const ChppGikLocomotionElement* ChppGikLocomotionPlan::activeElement ( double  inTime) const

Get the currently active task if any.

Returns
null pointer if no locomotion element is active at the given time

◆ addElement()

bool ChppGikLocomotionPlan::addElement ( ChppGikLocomotionElement inElement)

Add a locomotion element (the object is not copied).

Returns
false if the time frame taken by the added element overlaps with a previously added element

◆ clearElements()

void ChppGikLocomotionPlan::clearElements ( )

Delete entered elements (the object deleted)

◆ dataAtTime()

ChppGikLocomotionData* ChppGikLocomotionPlan::dataAtTime ( double  inTime)

Get all locomotion data at given time.

◆ endTime()

double ChppGikLocomotionPlan::endTime ( )

Get the end time according to entered elements.

◆ extraEndTime() [1/2]

double ChppGikLocomotionPlan::extraEndTime ( )

Get an extra end time.

◆ extraEndTime() [2/2]

void ChppGikLocomotionPlan::extraEndTime ( double  inDuration)

Set an extra end time.

◆ filterZMP()

bool ChppGikLocomotionPlan::filterZMP ( matrixNxP zmpError)

filter ZMP trajectory.

◆ getWeightsAtTime()

bool ChppGikLocomotionPlan::getWeightsAtTime ( double  inTime,
vectorN outWeights 
)

Get an appropriate joints weighting vecotr according to current task.

Returns
False if given time is out of bounds

◆ getZMPAtTime()

bool ChppGikLocomotionPlan::getZMPAtTime ( double  inTime,
vectorN outZMP 
)

Get planned ZMP at time inTime.

Returns
False if given time is out of bounds

◆ solve()

bool ChppGikLocomotionPlan::solve ( )

Solve = based on the entered elements do:

  • plan ZMP
  • plan COM
  • append feet motion to MotionPlan
    Returns
    false if any of the above steps fail

◆ startTime()

double ChppGikLocomotionPlan::startTime ( )

Get the start time according to entered elements.

◆ supportFootJoint()

CjrlJoint* ChppGikLocomotionPlan::supportFootJoint ( double  inTime)

Get the default support foot joint at the given time.

Returns
null pointer if no locomotion element is active at the given time