Loading...
Searching...
No Matches
multicontact_api::scenario::ContactSequenceTpl< _ContactPhase > Struct Template Reference

#include <multicontact-api/scenario/contact-sequence.hpp>

Inheritance diagram for multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >:
Collaboration diagram for multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >:

Public Types

typedef ContactPhase::Scalar Scalar
 
typedef ContactPhase::t_strings t_strings
 
typedef ContactPhase::SE3 SE3
 
typedef std::vector< ContactPhaseContactPhaseVector
 
typedef ndcurves::pointX_t pointX_t
 
typedef ndcurves::transform_t transform_t
 
typedef ndcurves::curve_abc_t curve_t
 
typedef ndcurves::curve_SE3_t curve_SE3_t
 
typedef std::shared_ptr< curve_tcurve_ptr
 
typedef std::shared_ptr< curve_SE3_tcurve_SE3_ptr
 
typedef ndcurves::piecewise_t piecewise_t
 
typedef ndcurves::piecewise_SE3_t piecewise_SE3_t
 
typedef ndcurves::SE3Curve_t SE3Curve_t
 
typedef ndcurves::polynomial_t polynomial_t
 

Public Member Functions

 ContactSequenceTpl (const size_t size=0)
 
 ContactSequenceTpl (const ContactSequenceTpl &other)
 Copy contructor.
 
size_t size () const
 
bool operator== (const ContactSequenceTpl &other) const
 
bool operator!= (const ContactSequenceTpl &other) const
 
void resize (const size_t size)
 
size_t append (const ContactPhase &contactPhase)
 append Add the given Phase at the end of the sequence
 
const ContactPhaseVector contactPhases () const
 contactPhases return a Const copy of the contact phase vector in this sequence. Prefer accessing the contact phases through the contactPhase(id) as this one create a copy
 
ContactPhasecontactPhase (const size_t id)
 contactPhase return a reference to the contactPhase stored at the given Id
 
void removePhase (const size_t id)
 removePhase remove the given contactPhase from the sequence
 
void breakContact (const std::string &eeName, const double phaseDuration=-1)
 breakContact Add a new contactPhase at the end of the current ContactSequence, The new ContactPhase have the same ContactPatchs as the last phase of the sequence, with the exeption of the given contact removed. It copy all the 'final' values of the last phase as 'initial' values of the new phase. It also set the duration of the previous last phase.
 
void createContact (const std::string &eeName, const ContactPatch &patch, const double phaseDuration=-1)
 createContact Add a new contactPhase at the end of the current ContactSequence, The new ContactPhase have the same ContactPatchs as the last phase of the sequence, with the exeption of the given contact added.
 
void moveEffectorToPlacement (const std::string &eeName, const ContactPatch::SE3 &placement, const double durationBreak=-1, const double durationCreate=-1)
 moveEffectorToPlacement Add two new phases at the end of the current ContactSequence,
 
void moveEffectorOf (const std::string &eeName, const ContactPatch::SE3 &transform, const double durationBreak=-1, const double durationCreate=-1)
 moveEffectorOf similar to moveEffectorToPlacement exept that the new placement is defined from the previous placement and a given transform applied.
 
bool haveTimings () const
 haveTimings Check if all the time intervals are defined and consistent (ie. the time always increase and the final time of one phase is equal to the initial one of the newt phase)
 
bool haveConsistentContacts () const
 haveConsistentContacts check that there is always one contact change between adjacent phases in the sequence and that there isn't any phase without any contact.
 
bool haveCOMvalues () const
 haveCOMvalues Check that the initial and final CoM position values are defined for all phases Also check that the initial values of one phase correspond to the final values of the previous ones.
 
bool haveAMvalues () const
 haveAMvalues Check that the initial and final AM values are defined for all phases Also check that the initial values of one phase correspond to the final values of the previous ones.
 
bool haveCentroidalValues () const
 haveCentroidalValues Check that the initial and final CoM position and AM values are defined for all phases Also check that the initial values of one phase correspond to the final values of the previous ones.
 
bool haveConfigurationsValues () const
 haveConfigurationsValues Check that the initial and final configuration are defined for all phases Also check that the initial values of one phase correspond to the final values of the previous ones.
 
bool haveCOMtrajectories () const
 haveCOMtrajectories check that a c, dc and ddc trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase
 
bool haveAMtrajectories () const
 haveAMtrajectories check that a L and dL trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase
 
bool haveCentroidalTrajectories () const
 haveCentroidalTrajectories check that all centroidal trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase
 
bool haveEffectorsTrajectories (const Scalar prec=Eigen::NumTraits< Scalar >::dummy_precision(), const bool use_rotation=true) const
 haveEffectorsTrajectories check that for each phase preceeding a contact creation, an SE3 trajectory is defined for the effector that will be in contact. Also check that this trajectory is defined on the time-interval of the phase. Also check that the trajectory correctly end at the placement defined for the contact in the next phase. If this effector was in contact in the previous phase, it check that the trajectory start at the previous contact placement.
 
bool haveJointsTrajectories () const
 haveJointsTrajectories Check that a q trajectory is defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase
 
bool haveJointsDerivativesTrajectories () const
 haveJointsDerivativesTrajectories Check that a dq and ddq trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase
 
bool haveTorquesTrajectories () const
 haveJointsTrajectories Check that a joint torque trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase
 
bool haveContactForcesTrajectories () const
 haveJointsTrajectories Check that a contact force trajectory exist for each active contact Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase
 
bool haveRootTrajectories () const
 haveRootTrajectories check that a root trajectory exist for each contact phases. Also check that it start and end at the correct time interval
 
bool haveFriction () const
 haveFriction check that all the contact patch used in the sequence have a friction coefficient initialized
 
bool haveContactModelDefined () const
 haveContactModelDefined check that all the contact patch have a contact_model defined
 
bool haveZMPtrajectories ()
 haveZMPtrajectories check that all the contact phases have a zmp trajectory
 
t_strings getAllEffectorsInContact () const
 getAllEffectorsInContact return a vector of names of all the effectors used to create contacts during the sequence
 
piecewise_t concatenateCtrajectories () const
 concatenateCtrajectories Return a piecewise curve which is the concatenation of the m_c curves for each contact phases in the sequence.
 
piecewise_t concatenateDCtrajectories () const
 concatenateDCtrajectories Return a piecewise curve which is the concatenation of the m_dc curves for each contact phases in the sequence.
 
piecewise_t concatenateDDCtrajectories () const
 concatenateDDCtrajectories Return a piecewise curve which is the concatenation of the m_ddc curves for each contact phases in the sequence.
 
piecewise_t concatenateLtrajectories () const
 concatenateLtrajectories Return a piecewise curve which is the concatenation of the m_L curves for each contact phases in the sequence.
 
piecewise_t concatenateDLtrajectories () const
 concatenateDLtrajectories Return a piecewise curve which is the concatenation of the m_dL curves for each contact phases in the sequence.
 
piecewise_t concatenateZMPtrajectories () const
 concatenateZMPtrajectories Return a piecewise curve which is the concatenation of the m_zmp curves for each contact phases in the sequence.
 
piecewise_t concatenateWrenchTrajectories () const
 concatenateWrenchTrajectories Return a piecewise curve which is the concatenation of the m_wrench curves for each contact phases in the sequence.
 
piecewise_t concatenateQtrajectories () const
 concatenateQtrajectories Return a piecewise curve which is the concatenation of the m_q curves for each contact phases in the sequence.
 
piecewise_t concatenateDQtrajectories () const
 concatenateDQtrajectories Return a piecewise curve which is the concatenation of the m_dq curves for each contact phases in the sequence.
 
piecewise_t concatenateDDQtrajectories () const
 concatenateDDQtrajectories Return a piecewise curve which is the concatenation of the m_ddq curves for each contact phases in the sequence.
 
piecewise_t concatenateTauTrajectories () const
 concatenateTauTrajectories Return a piecewise curve which is the concatenation of the m_tau curves for each contact phases in the sequence.
 
piecewise_SE3_t concatenateRootTrajectories () const
 concatenateRootTrajectories Return a piecewise curve which is the concatenation of the m_root curves for each contact phases in the sequence.
 
piecewise_SE3_t concatenateEffectorTrajectories (const std::string &eeName) const
 concatenateEffectorTrajectories Return a piecewise curve which is the concatenation of the effectors trajectories curves for the given effector for each contact phases in the sequence. During the phases where no effector trajectories are defined, the trajectory is constant with the value of the last phase where it was defined.
 
piecewise_t concatenateContactForceTrajectories (const std::string &eeName) const
 concatenateContactForceTrajectories Return a piecewise curve which is the concatenation of the contact forces for the given effector for each contact phases in the sequence. During the phases where no contact forces are defined, the trajectory is constant with the value of 0.
 
piecewise_t concatenateNormalForceTrajectories (const std::string &eeName) const
 concatenateNormalForceTrajectories Return a piecewise curve which is the concatenation of the contact normal forces for the given effector for each contact phases in the sequence. During the phases where no contact normal forces are defined, the trajectory is constant with the value of 0.
 
ContactPhasephaseAtTime (const double time)
 phaseAtTime return a phase of the sequence such that : phase.timeInitial <= t < phase.timeFinal if t equal to the last phase timeFinal, this index is returned
 
int phaseIdAtTime (const double time) const
 phaseIdAtTime return the index of a phase in the sequence such that : phase.timeInitial <= t < phase.timeFinal if t equal to the last phase timeFinal, this index is returned
 
- Public Member Functions inherited from multicontact_api::serialization::Serializable< ContactSequenceTpl< _ContactPhase > >
void loadFromText (const std::string &filename)
 Loads a Derived object from a text file.
 
void saveAsText (const std::string &filename) const
 Saved a Derived object as a text file.
 
void loadFromXML (const std::string &filename, const std::string &tag_name)
 Loads a Derived object from an XML file.
 
void saveAsXML (const std::string &filename, const std::string &tag_name) const
 Saved a Derived object as an XML file.
 
void loadFromBinary (const std::string &filename)
 Loads a Derived object from an binary file.
 
void saveAsBinary (const std::string &filename) const
 Saved a Derived object as an binary file.
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _ContactPhase ContactPhase
 
ContactPhaseVector m_contact_phases
 

Friends

class boost::serialization::access
 

Member Typedef Documentation

◆ ContactPhaseVector

template<class _ContactPhase >
typedef std::vector<ContactPhase> multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::ContactPhaseVector

◆ curve_ptr

template<class _ContactPhase >
typedef std::shared_ptr<curve_t> multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::curve_ptr

◆ curve_SE3_ptr

template<class _ContactPhase >
typedef std::shared_ptr<curve_SE3_t> multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::curve_SE3_ptr

◆ curve_SE3_t

template<class _ContactPhase >
typedef ndcurves::curve_SE3_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::curve_SE3_t

◆ curve_t

template<class _ContactPhase >
typedef ndcurves::curve_abc_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::curve_t

◆ piecewise_SE3_t

template<class _ContactPhase >
typedef ndcurves::piecewise_SE3_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::piecewise_SE3_t

◆ piecewise_t

template<class _ContactPhase >
typedef ndcurves::piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::piecewise_t

◆ pointX_t

template<class _ContactPhase >
typedef ndcurves::pointX_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::pointX_t

◆ polynomial_t

template<class _ContactPhase >
typedef ndcurves::polynomial_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::polynomial_t

◆ Scalar

template<class _ContactPhase >
typedef ContactPhase::Scalar multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::Scalar

◆ SE3

template<class _ContactPhase >
typedef ContactPhase::SE3 multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::SE3

◆ SE3Curve_t

template<class _ContactPhase >
typedef ndcurves::SE3Curve_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::SE3Curve_t

◆ t_strings

template<class _ContactPhase >
typedef ContactPhase::t_strings multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::t_strings

◆ transform_t

template<class _ContactPhase >
typedef ndcurves::transform_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::transform_t

Constructor & Destructor Documentation

◆ ContactSequenceTpl() [1/2]

template<class _ContactPhase >
multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::ContactSequenceTpl ( const size_t  size = 0)
inline

◆ ContactSequenceTpl() [2/2]

template<class _ContactPhase >
multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::ContactSequenceTpl ( const ContactSequenceTpl< _ContactPhase > &  other)
inline

Copy contructor.

Member Function Documentation

◆ append()

template<class _ContactPhase >
size_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::append ( const ContactPhase contactPhase)
inline

append Add the given Phase at the end of the sequence

Parameters
contactPhasethe phase to end
Returns
The id of the phase added in the sequence

◆ breakContact()

template<class _ContactPhase >
void multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::breakContact ( const std::string &  eeName,
const double  phaseDuration = -1 
)
inline

breakContact Add a new contactPhase at the end of the current ContactSequence, The new ContactPhase have the same ContactPatchs as the last phase of the sequence, with the exeption of the given contact removed. It copy all the 'final' values of the last phase as 'initial' values of the new phase. It also set the duration of the previous last phase.

Parameters
eeNamethe name of the effector to remove from contact
phaseDurationif provided, the duration of the previous last phase of the sequence is set to this value (it is thus the duration BEFORE breaking the contact)
Exceptions
invalid_argumentif the phaseDuration is provided but the last phase do not have a time-range defined
invalid_argumentif eeName is not in contact in the last phase of the sequence

◆ concatenateContactForceTrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateContactForceTrajectories ( const std::string &  eeName) const
inline

concatenateContactForceTrajectories Return a piecewise curve which is the concatenation of the contact forces for the given effector for each contact phases in the sequence. During the phases where no contact forces are defined, the trajectory is constant with the value of 0.

Parameters
eeNamethe effector name
Returns

◆ concatenateCtrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateCtrajectories ( ) const
inline

concatenateCtrajectories Return a piecewise curve which is the concatenation of the m_c curves for each contact phases in the sequence.

Returns

◆ concatenateDCtrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateDCtrajectories ( ) const
inline

concatenateDCtrajectories Return a piecewise curve which is the concatenation of the m_dc curves for each contact phases in the sequence.

Returns

◆ concatenateDDCtrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateDDCtrajectories ( ) const
inline

concatenateDDCtrajectories Return a piecewise curve which is the concatenation of the m_ddc curves for each contact phases in the sequence.

Returns

◆ concatenateDDQtrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateDDQtrajectories ( ) const
inline

concatenateDDQtrajectories Return a piecewise curve which is the concatenation of the m_ddq curves for each contact phases in the sequence.

Returns

◆ concatenateDLtrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateDLtrajectories ( ) const
inline

concatenateDLtrajectories Return a piecewise curve which is the concatenation of the m_dL curves for each contact phases in the sequence.

Returns

◆ concatenateDQtrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateDQtrajectories ( ) const
inline

concatenateDQtrajectories Return a piecewise curve which is the concatenation of the m_dq curves for each contact phases in the sequence.

Returns

◆ concatenateEffectorTrajectories()

template<class _ContactPhase >
piecewise_SE3_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateEffectorTrajectories ( const std::string &  eeName) const
inline

concatenateEffectorTrajectories Return a piecewise curve which is the concatenation of the effectors trajectories curves for the given effector for each contact phases in the sequence. During the phases where no effector trajectories are defined, the trajectory is constant with the value of the last phase where it was defined.

Parameters
eeNamethe effector name
Returns

◆ concatenateLtrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateLtrajectories ( ) const
inline

concatenateLtrajectories Return a piecewise curve which is the concatenation of the m_L curves for each contact phases in the sequence.

Returns

◆ concatenateNormalForceTrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateNormalForceTrajectories ( const std::string &  eeName) const
inline

concatenateNormalForceTrajectories Return a piecewise curve which is the concatenation of the contact normal forces for the given effector for each contact phases in the sequence. During the phases where no contact normal forces are defined, the trajectory is constant with the value of 0.

Parameters
eeNamethe effector name
Returns

◆ concatenateQtrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateQtrajectories ( ) const
inline

concatenateQtrajectories Return a piecewise curve which is the concatenation of the m_q curves for each contact phases in the sequence.

Returns

◆ concatenateRootTrajectories()

template<class _ContactPhase >
piecewise_SE3_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateRootTrajectories ( ) const
inline

concatenateRootTrajectories Return a piecewise curve which is the concatenation of the m_root curves for each contact phases in the sequence.

Returns

◆ concatenateTauTrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateTauTrajectories ( ) const
inline

concatenateTauTrajectories Return a piecewise curve which is the concatenation of the m_tau curves for each contact phases in the sequence.

Returns

◆ concatenateWrenchTrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateWrenchTrajectories ( ) const
inline

concatenateWrenchTrajectories Return a piecewise curve which is the concatenation of the m_wrench curves for each contact phases in the sequence.

Returns

◆ concatenateZMPtrajectories()

template<class _ContactPhase >
piecewise_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::concatenateZMPtrajectories ( ) const
inline

concatenateZMPtrajectories Return a piecewise curve which is the concatenation of the m_zmp curves for each contact phases in the sequence.

Returns

◆ contactPhase()

template<class _ContactPhase >
ContactPhase & multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::contactPhase ( const size_t  id)
inline

contactPhase return a reference to the contactPhase stored at the given Id

Parameters
idthe desired Id in the contact sequence
Returns
a reference to the ContactPhase

◆ contactPhases()

template<class _ContactPhase >
const ContactPhaseVector multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::contactPhases ( ) const
inline

contactPhases return a Const copy of the contact phase vector in this sequence. Prefer accessing the contact phases through the contactPhase(id) as this one create a copy

Returns
a Const copy of the contact phase vector in this sequence

◆ createContact()

template<class _ContactPhase >
void multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::createContact ( const std::string &  eeName,
const ContactPatch patch,
const double  phaseDuration = -1 
)
inline

createContact Add a new contactPhase at the end of the current ContactSequence, The new ContactPhase have the same ContactPatchs as the last phase of the sequence, with the exeption of the given contact added.

Parameters
eeNamethe name of the effector used to create contact
patchthe ContactPatch of the new contact
phaseDurationif provided, the duration of the previous last phase of the sequence is set to this value (it is thus the duration BEFORE creating the contact)
Exceptions
invalid_argumentif the phaseDuration is provided but the last phase do not have a time-range defined
invalid_argumentif eeName is already in contact in the last phase of the sequence

◆ getAllEffectorsInContact()

template<class _ContactPhase >
t_strings multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::getAllEffectorsInContact ( ) const
inline

getAllEffectorsInContact return a vector of names of all the effectors used to create contacts during the sequence

Returns

◆ haveAMtrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveAMtrajectories ( ) const
inline

haveAMtrajectories check that a L and dL trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase

Returns

◆ haveAMvalues()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveAMvalues ( ) const
inline

haveAMvalues Check that the initial and final AM values are defined for all phases Also check that the initial values of one phase correspond to the final values of the previous ones.

Returns

◆ haveCentroidalTrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveCentroidalTrajectories ( ) const
inline

haveCentroidalTrajectories check that all centroidal trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase

Returns

◆ haveCentroidalValues()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveCentroidalValues ( ) const
inline

haveCentroidalValues Check that the initial and final CoM position and AM values are defined for all phases Also check that the initial values of one phase correspond to the final values of the previous ones.

Returns

◆ haveCOMtrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveCOMtrajectories ( ) const
inline

haveCOMtrajectories check that a c, dc and ddc trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase

Returns

◆ haveCOMvalues()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveCOMvalues ( ) const
inline

haveCOMvalues Check that the initial and final CoM position values are defined for all phases Also check that the initial values of one phase correspond to the final values of the previous ones.

Returns

◆ haveConfigurationsValues()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveConfigurationsValues ( ) const
inline

haveConfigurationsValues Check that the initial and final configuration are defined for all phases Also check that the initial values of one phase correspond to the final values of the previous ones.

Returns

◆ haveConsistentContacts()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveConsistentContacts ( ) const
inline

haveConsistentContacts check that there is always one contact change between adjacent phases in the sequence and that there isn't any phase without any contact.

Returns

◆ haveContactForcesTrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveContactForcesTrajectories ( ) const
inline

haveJointsTrajectories Check that a contact force trajectory exist for each active contact Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase

Returns

◆ haveContactModelDefined()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveContactModelDefined ( ) const
inline

haveContactModelDefined check that all the contact patch have a contact_model defined

Returns

◆ haveEffectorsTrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveEffectorsTrajectories ( const Scalar  prec = Eigen::NumTraits<Scalar>::dummy_precision(),
const bool  use_rotation = true 
) const
inline

haveEffectorsTrajectories check that for each phase preceeding a contact creation, an SE3 trajectory is defined for the effector that will be in contact. Also check that this trajectory is defined on the time-interval of the phase. Also check that the trajectory correctly end at the placement defined for the contact in the next phase. If this effector was in contact in the previous phase, it check that the trajectory start at the previous contact placement.

Returns

◆ haveFriction()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveFriction ( ) const
inline

haveFriction check that all the contact patch used in the sequence have a friction coefficient initialized

Returns

◆ haveJointsDerivativesTrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveJointsDerivativesTrajectories ( ) const
inline

haveJointsDerivativesTrajectories Check that a dq and ddq trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase

Returns

◆ haveJointsTrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveJointsTrajectories ( ) const
inline

haveJointsTrajectories Check that a q trajectory is defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase

Returns

◆ haveRootTrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveRootTrajectories ( ) const
inline

haveRootTrajectories check that a root trajectory exist for each contact phases. Also check that it start and end at the correct time interval

Returns

◆ haveTimings()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveTimings ( ) const
inline

haveTimings Check if all the time intervals are defined and consistent (ie. the time always increase and the final time of one phase is equal to the initial one of the newt phase)

Returns
true if the sequence is consistent, false otherwise

◆ haveTorquesTrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveTorquesTrajectories ( ) const
inline

haveJointsTrajectories Check that a joint torque trajectories are defined for each phases Also check that the time interval of this trajectories matches the one of the phase and that the trajectories start and end and the correct values defined in each phase

Returns

◆ haveZMPtrajectories()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::haveZMPtrajectories ( )
inline

haveZMPtrajectories check that all the contact phases have a zmp trajectory

Returns

◆ moveEffectorOf()

template<class _ContactPhase >
void multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::moveEffectorOf ( const std::string &  eeName,
const ContactPatch::SE3 transform,
const double  durationBreak = -1,
const double  durationCreate = -1 
)
inline

moveEffectorOf similar to moveEffectorToPlacement exept that the new placement is defined from the previous placement and a given transform applied.

Parameters
eeNamethe name of the effector used to create contact
transformthe transform applied to the placement of the contact in the last phase of the sequence
durationBreakthe duration of the previous last phase of the sequence (it is thus the duration BEFORE breaking the contact)
durationCreatethe duration of the first new ContactPhase (it is thus the duration BEFORE creating the contact)
Exceptions
invalid_argumentif the phaseDuration is provided but the last phase do not have a time-range defined
invalid_argumentif eeName is not in contact in the last phase of the sequence

◆ moveEffectorToPlacement()

template<class _ContactPhase >
void multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::moveEffectorToPlacement ( const std::string &  eeName,
const ContactPatch::SE3 placement,
const double  durationBreak = -1,
const double  durationCreate = -1 
)
inline

moveEffectorToPlacement Add two new phases at the end of the current ContactSequence,

  • it break the contact with eeName
  • it create the contact with eeName at the given placement. It copy all the 'final' values of the last phase as 'initial' values of the new phase. It also set the duration of the previous last phase.
    Parameters
    eeNamethe name of the effector used to create contact
    placementthe new placement for the contact of eeName
    durationBreakthe duration of the previous last phase of the sequence (it is thus the duration BEFORE breaking the contact)
    durationCreatethe duration of the first new ContactPhase (it is thus the duration BEFORE creating the contact)
    Exceptions
    invalid_argumentif the phaseDuration is provided but the last phase do not have a time-range defined
    invalid_argumentif eeName is not in contact in the last phase of the sequence

◆ operator!=()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::operator!= ( const ContactSequenceTpl< _ContactPhase > &  other) const
inline

◆ operator==()

template<class _ContactPhase >
bool multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::operator== ( const ContactSequenceTpl< _ContactPhase > &  other) const
inline

◆ phaseAtTime()

template<class _ContactPhase >
ContactPhase & multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::phaseAtTime ( const double  time)
inline

phaseAtTime return a phase of the sequence such that : phase.timeInitial <= t < phase.timeFinal if t equal to the last phase timeFinal, this index is returned

Parameters
time
Returns
the phase whose time interval contains 'time'
Exceptions
invalid_argumenterror if no phase are found for this time

◆ phaseIdAtTime()

template<class _ContactPhase >
int multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::phaseIdAtTime ( const double  time) const
inline

phaseIdAtTime return the index of a phase in the sequence such that : phase.timeInitial <= t < phase.timeFinal if t equal to the last phase timeFinal, this index is returned

Parameters
time
Returns
the index of the phase whose time interval contain 'time', -1 if no phase are found

◆ removePhase()

template<class _ContactPhase >
void multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::removePhase ( const size_t  id)
inline

removePhase remove the given contactPhase from the sequence

Parameters
idthe Id of the phase to remove

◆ resize()

template<class _ContactPhase >
void multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::resize ( const size_t  size)
inline

◆ size()

template<class _ContactPhase >
size_t multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::size ( ) const
inline

Friends And Related Symbol Documentation

◆ boost::serialization::access

template<class _ContactPhase >
friend class boost::serialization::access
friend

Member Data Documentation

◆ ContactPhase

template<class _ContactPhase >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _ContactPhase multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::ContactPhase

◆ m_contact_phases

template<class _ContactPhase >
ContactPhaseVector multicontact_api::scenario::ContactSequenceTpl< _ContactPhase >::m_contact_phases

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