Blender  V3.3
Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
iTaSC::ConstraintSet Class Referenceabstract

#include <ConstraintSet.hpp>

Inheritance diagram for iTaSC::ConstraintSet:
iTaSC::CopyPose iTaSC::Distance

Public Member Functions

 ConstraintSet (unsigned int nc, double accuracy, unsigned int maximum_iterations)
 
 ConstraintSet ()
 
virtual ~ConstraintSet ()
 
virtual EIGEN_MAKE_ALIGNED_OPERATOR_NEW bool registerCallback (ConstraintCallback _function, void *_param)
 
virtual const e_vectorgetControlOutput () const
 
virtual const ConstraintValuesgetControlParameters (unsigned int *_nvalues)=0
 
virtual bool setControlParameters (ConstraintValues *_values, unsigned int _nvalues, double timestep=0.0)=0
 
bool setControlParameter (int id, ConstraintAction action, double value, double timestep=0.0)
 
virtual const e_matrix6getJf () const
 
virtual const KDL::FramegetPose () const
 
virtual const e_matrixgetCf () const
 
virtual const e_vectorgetWy () const
 
virtual void setWy (const e_vector &Wy_in)
 
virtual void setJointVelocity (const e_vector chidot_in)
 
virtual unsigned int getNrOfConstraints ()
 
void substep (bool _substep)
 
bool substep ()
 

Protected Member Functions

virtual void modelUpdate (KDL::Frame &_external_pose, const Timestamp &timestamp)
 
virtual void updateKinematics (const Timestamp &timestamp)=0
 
virtual void pushCache (const Timestamp &timestamp)=0
 
virtual void updateJacobian ()=0
 
virtual void updateControlOutput (const Timestamp &timestamp)=0
 
virtual void initCache (Cache *_cache)=0
 
virtual bool initialise (KDL::Frame &init_pose)
 
virtual void reset (unsigned int nc, double accuracy, unsigned int maximum_iterations)
 
virtual bool closeLoop ()
 
virtual double getMaxTimestep (double &timestep)
 

Protected Attributes

unsigned int m_nc
 
e_scalar m_maxDeltaChi
 
e_matrix m_Cf
 
e_vector m_Wy
 
e_vector m_y
 
e_vector m_ydot
 
e_vector6 m_chi
 
e_vector6 m_chidot
 
e_vector6 m_S
 
e_vector6 m_temp
 
e_vector6 m_tdelta
 
e_matrix6 m_Jf
 
e_matrix6 m_U
 
e_matrix6 m_V
 
e_matrix6 m_B
 
e_matrix6 m_Jf_inv
 
KDL::Frame m_internalPose
 
KDL::Frame m_externalPose
 
ConstraintCallback m_constraintCallback
 
voidm_constraintParam
 
voidm_poseParam
 
bool m_toggle
 
bool m_substep
 
double m_threshold
 
unsigned int m_maxIter
 

Friends

class Scene
 

Detailed Description

Definition at line 51 of file ConstraintSet.hpp.

Constructor & Destructor Documentation

◆ ConstraintSet() [1/2]

iTaSC::ConstraintSet::ConstraintSet ( unsigned int  nc,
double  accuracy,
unsigned int  maximum_iterations 
)

Definition at line 13 of file ConstraintSet.cpp.

References e_scalar, and m_maxDeltaChi.

◆ ConstraintSet() [2/2]

iTaSC::ConstraintSet::ConstraintSet ( )

Definition at line 30 of file ConstraintSet.cpp.

References e_scalar, and m_maxDeltaChi.

◆ ~ConstraintSet()

iTaSC::ConstraintSet::~ConstraintSet ( )
virtual

Definition at line 61 of file ConstraintSet.cpp.

Member Function Documentation

◆ closeLoop()

bool iTaSC::ConstraintSet::closeLoop ( )
protectedvirtual

◆ getCf()

virtual const e_matrix& iTaSC::ConstraintSet::getCf ( ) const
inlinevirtual

Definition at line 102 of file ConstraintSet.hpp.

References m_Cf.

◆ getControlOutput()

virtual const e_vector& iTaSC::ConstraintSet::getControlOutput ( ) const
inlinevirtual

Definition at line 95 of file ConstraintSet.hpp.

References m_ydot.

◆ getControlParameters()

virtual const ConstraintValues* iTaSC::ConstraintSet::getControlParameters ( unsigned int *  _nvalues)
pure virtual

Implemented in iTaSC::Distance, and iTaSC::CopyPose.

Referenced by execute_scene().

◆ getJf()

virtual const e_matrix6& iTaSC::ConstraintSet::getJf ( ) const
inlinevirtual

Definition at line 100 of file ConstraintSet.hpp.

References m_Jf.

◆ getMaxTimestep()

double iTaSC::ConstraintSet::getMaxTimestep ( double timestep)
protectedvirtual

Reimplemented in iTaSC::CopyPose.

Definition at line 78 of file ConstraintSet.cpp.

References e_scalar, m_chidot, and m_maxDeltaChi.

◆ getNrOfConstraints()

virtual unsigned int iTaSC::ConstraintSet::getNrOfConstraints ( )
inlinevirtual

Definition at line 108 of file ConstraintSet.hpp.

References m_nc.

◆ getPose()

virtual const KDL::Frame& iTaSC::ConstraintSet::getPose ( ) const
inlinevirtual

Definition at line 101 of file ConstraintSet.hpp.

References m_internalPose.

◆ getWy()

virtual const e_vector& iTaSC::ConstraintSet::getWy ( ) const
inlinevirtual

Definition at line 104 of file ConstraintSet.hpp.

References m_Wy.

◆ initCache()

virtual void iTaSC::ConstraintSet::initCache ( Cache _cache)
protectedpure virtual

Implemented in iTaSC::Distance, and iTaSC::CopyPose.

◆ initialise()

bool iTaSC::ConstraintSet::initialise ( KDL::Frame init_pose)
protectedvirtual

Reimplemented in iTaSC::Distance, and iTaSC::CopyPose.

Definition at line 87 of file ConstraintSet.cpp.

References closeLoop(), m_externalPose, m_maxIter, and updateJacobian().

◆ modelUpdate()

void iTaSC::ConstraintSet::modelUpdate ( KDL::Frame _external_pose,
const Timestamp timestamp 
)
protectedvirtual

◆ pushCache()

virtual void iTaSC::ConstraintSet::pushCache ( const Timestamp timestamp)
protectedpure virtual

Implemented in iTaSC::Distance, and iTaSC::CopyPose.

◆ registerCallback()

virtual EIGEN_MAKE_ALIGNED_OPERATOR_NEW bool iTaSC::ConstraintSet::registerCallback ( ConstraintCallback  _function,
void _param 
)
inlinevirtual

Definition at line 88 of file ConstraintSet.hpp.

References m_constraintCallback, and m_constraintParam.

Referenced by convert_tree().

◆ reset()

void iTaSC::ConstraintSet::reset ( unsigned int  nc,
double  accuracy,
unsigned int  maximum_iterations 
)
protectedvirtual

◆ setControlParameter()

bool iTaSC::ConstraintSet::setControlParameter ( int  id,
ConstraintAction  action,
double  value,
double  timestep = 0.0 
)

◆ setControlParameters()

virtual bool iTaSC::ConstraintSet::setControlParameters ( ConstraintValues _values,
unsigned int  _nvalues,
double  timestep = 0.0 
)
pure virtual

Implemented in iTaSC::Distance, and iTaSC::CopyPose.

Referenced by setControlParameter().

◆ setJointVelocity()

virtual void iTaSC::ConstraintSet::setJointVelocity ( const e_vector  chidot_in)
inlinevirtual

Definition at line 106 of file ConstraintSet.hpp.

References m_chidot.

◆ setWy()

virtual void iTaSC::ConstraintSet::setWy ( const e_vector Wy_in)
inlinevirtual

Definition at line 105 of file ConstraintSet.hpp.

References m_Wy.

◆ substep() [1/2]

bool iTaSC::ConstraintSet::substep ( )
inline

Definition at line 110 of file ConstraintSet.hpp.

References m_substep.

◆ substep() [2/2]

void iTaSC::ConstraintSet::substep ( bool  _substep)
inline

Definition at line 109 of file ConstraintSet.hpp.

References m_substep.

Referenced by convert_tree().

◆ updateControlOutput()

virtual void iTaSC::ConstraintSet::updateControlOutput ( const Timestamp timestamp)
protectedpure virtual

Implemented in iTaSC::Distance, and iTaSC::CopyPose.

◆ updateJacobian()

virtual void iTaSC::ConstraintSet::updateJacobian ( )
protectedpure virtual

Implemented in iTaSC::Distance, and iTaSC::CopyPose.

Referenced by closeLoop(), initialise(), and modelUpdate().

◆ updateKinematics()

virtual void iTaSC::ConstraintSet::updateKinematics ( const Timestamp timestamp)
protectedpure virtual

Implemented in iTaSC::Distance, and iTaSC::CopyPose.

Friends And Related Function Documentation

◆ Scene

friend class Scene
friend

Definition at line 68 of file ConstraintSet.hpp.

Member Data Documentation

◆ m_B

e_matrix6 iTaSC::ConstraintSet::m_B
protected

Definition at line 58 of file ConstraintSet.hpp.

Referenced by closeLoop(), and reset().

◆ m_Cf

e_matrix iTaSC::ConstraintSet::m_Cf
protected

◆ m_chi

e_vector6 iTaSC::ConstraintSet::m_chi
protected

◆ m_chidot

e_vector6 iTaSC::ConstraintSet::m_chidot
protected

◆ m_constraintCallback

ConstraintCallback iTaSC::ConstraintSet::m_constraintCallback
protected

◆ m_constraintParam

void* iTaSC::ConstraintSet::m_constraintParam
protected

◆ m_externalPose

KDL::Frame iTaSC::ConstraintSet::m_externalPose
protected

◆ m_internalPose

KDL::Frame iTaSC::ConstraintSet::m_internalPose
protected

◆ m_Jf

e_matrix6 iTaSC::ConstraintSet::m_Jf
protected

◆ m_Jf_inv

e_matrix6 iTaSC::ConstraintSet::m_Jf_inv
protected

Definition at line 58 of file ConstraintSet.hpp.

Referenced by closeLoop(), and reset().

◆ m_maxDeltaChi

e_scalar iTaSC::ConstraintSet::m_maxDeltaChi
protected

◆ m_maxIter

unsigned int iTaSC::ConstraintSet::m_maxIter
protected

Definition at line 66 of file ConstraintSet.hpp.

Referenced by initialise(), and reset().

◆ m_nc

unsigned int iTaSC::ConstraintSet::m_nc
protected

Definition at line 53 of file ConstraintSet.hpp.

Referenced by iTaSC::CopyPose::CopyPose(), getNrOfConstraints(), and reset().

◆ m_poseParam

void* iTaSC::ConstraintSet::m_poseParam
protected

Definition at line 62 of file ConstraintSet.hpp.

◆ m_S

e_vector6 iTaSC::ConstraintSet::m_S
protected

Definition at line 57 of file ConstraintSet.hpp.

Referenced by closeLoop(), and reset().

◆ m_substep

bool iTaSC::ConstraintSet::m_substep
protected

◆ m_tdelta

e_vector6 iTaSC::ConstraintSet::m_tdelta
protected

Definition at line 57 of file ConstraintSet.hpp.

Referenced by closeLoop(), and reset().

◆ m_temp

e_vector6 iTaSC::ConstraintSet::m_temp
protected

Definition at line 57 of file ConstraintSet.hpp.

Referenced by closeLoop(), and reset().

◆ m_threshold

double iTaSC::ConstraintSet::m_threshold
protected

Definition at line 65 of file ConstraintSet.hpp.

Referenced by closeLoop(), iTaSC::Distance::closeLoop(), and reset().

◆ m_toggle

bool iTaSC::ConstraintSet::m_toggle
protected

Definition at line 63 of file ConstraintSet.hpp.

◆ m_U

e_matrix6 iTaSC::ConstraintSet::m_U
protected

Definition at line 58 of file ConstraintSet.hpp.

Referenced by closeLoop(), and reset().

◆ m_V

e_matrix6 iTaSC::ConstraintSet::m_V
protected

Definition at line 58 of file ConstraintSet.hpp.

Referenced by closeLoop(), and reset().

◆ m_Wy

e_vector iTaSC::ConstraintSet::m_Wy
protected

◆ m_y

e_vector iTaSC::ConstraintSet::m_y
protected

Definition at line 56 of file ConstraintSet.hpp.

Referenced by reset().

◆ m_ydot

e_vector iTaSC::ConstraintSet::m_ydot
protected

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