Blender V2.61 - r43446

iTaSC::ConstraintSet Class Reference

#include <ConstraintSet.hpp>

Inheritance diagram for iTaSC::ConstraintSet:

List of all members.

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_vector & getControlOutput () 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_matrix6 & getJf () const
virtual const KDL::FramegetPose () const
virtual const e_matrix & getCf () const
virtual const e_vector & getWy () 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
void * m_constraintParam
void * m_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

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

Definition at line 34 of file ConstraintSet.cpp.

References e_scalar.

iTaSC::ConstraintSet::~ConstraintSet ( ) [virtual]

Definition at line 65 of file ConstraintSet.cpp.


Member Function Documentation

bool iTaSC::ConstraintSet::closeLoop ( ) [protected, virtual]

Reimplemented in iTaSC::Distance.

Definition at line 143 of file ConstraintSet.cpp.

Referenced by modelUpdate().

virtual const e_matrix& iTaSC::ConstraintSet::getCf ( ) const [inline, virtual]

Definition at line 102 of file ConstraintSet.hpp.

References m_Cf.

virtual const e_vector& iTaSC::ConstraintSet::getControlOutput ( ) const [inline, virtual]

Definition at line 95 of file ConstraintSet.hpp.

References m_ydot.

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

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

Referenced by execute_scene().

virtual const e_matrix6& iTaSC::ConstraintSet::getJf ( ) const [inline, virtual]

Definition at line 100 of file ConstraintSet.hpp.

References m_Jf.

double iTaSC::ConstraintSet::getMaxTimestep ( double &  timestep) [protected, virtual]

Reimplemented in iTaSC::CopyPose.

Definition at line 82 of file ConstraintSet.cpp.

References e_scalar, m_chidot, and m_maxDeltaChi.

virtual unsigned int iTaSC::ConstraintSet::getNrOfConstraints ( ) [inline, virtual]

Definition at line 108 of file ConstraintSet.hpp.

References m_nc.

Referenced by iTaSC::Scene::addConstraintSet().

virtual const KDL::Frame& iTaSC::ConstraintSet::getPose ( ) const [inline, virtual]

Definition at line 101 of file ConstraintSet.hpp.

References m_internalPose.

virtual const e_vector& iTaSC::ConstraintSet::getWy ( ) const [inline, virtual]

Definition at line 104 of file ConstraintSet.hpp.

References m_Wy.

virtual void iTaSC::ConstraintSet::initCache ( Cache _cache) [protected, pure virtual]

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

bool iTaSC::ConstraintSet::initialise ( KDL::Frame init_pose) [protected, virtual]

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

Definition at line 91 of file ConstraintSet.cpp.

void iTaSC::ConstraintSet::modelUpdate ( KDL::Frame _external_pose,
const Timestamp timestamp 
) [protected, virtual]
virtual void iTaSC::ConstraintSet::pushCache ( const Timestamp timestamp) [protected, pure virtual]

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

virtual EIGEN_MAKE_ALIGNED_OPERATOR_NEW bool iTaSC::ConstraintSet::registerCallback ( ConstraintCallback  _function,
void *  _param 
) [inline, virtual]

Definition at line 88 of file ConstraintSet.hpp.

References m_constraintCallback, and m_constraintParam.

Referenced by convert_tree().

void iTaSC::ConstraintSet::reset ( unsigned int  nc,
double  accuracy,
unsigned int  maximum_iterations 
) [protected, virtual]
virtual bool iTaSC::ConstraintSet::setControlParameters ( ConstraintValues _values,
unsigned int  _nvalues,
double  timestep = 0.0 
) [pure virtual]

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

Referenced by setControlParameter().

virtual void iTaSC::ConstraintSet::setJointVelocity ( const e_vector  chidot_in) [inline, virtual]

Definition at line 106 of file ConstraintSet.hpp.

References m_chidot.

virtual void iTaSC::ConstraintSet::setWy ( const e_vector &  Wy_in) [inline, virtual]

Definition at line 105 of file ConstraintSet.hpp.

References m_Wy.

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

Definition at line 109 of file ConstraintSet.hpp.

References m_substep.

Referenced by convert_tree().

bool iTaSC::ConstraintSet::substep ( ) [inline]

Definition at line 110 of file ConstraintSet.hpp.

References m_substep.

virtual void iTaSC::ConstraintSet::updateControlOutput ( const Timestamp timestamp) [protected, pure virtual]

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

virtual void iTaSC::ConstraintSet::updateJacobian ( ) [protected, pure virtual]

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

Referenced by modelUpdate().

virtual void iTaSC::ConstraintSet::updateKinematics ( const Timestamp timestamp) [protected, pure virtual]

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


Friends And Related Function Documentation

friend class Scene [friend]

Definition at line 68 of file ConstraintSet.hpp.


Member Data Documentation

e_matrix6 iTaSC::ConstraintSet::m_B [protected]

Definition at line 58 of file ConstraintSet.hpp.

Referenced by reset().

e_matrix iTaSC::ConstraintSet::m_Cf [protected]

Definition at line 55 of file ConstraintSet.hpp.

Referenced by getCf(), and reset().

e_vector6 iTaSC::ConstraintSet::m_chidot [protected]

Definition at line 57 of file ConstraintSet.hpp.

Referenced by getMaxTimestep(), modelUpdate(), reset(), and setJointVelocity().

e_matrix6 iTaSC::ConstraintSet::m_Jf [protected]

Definition at line 58 of file ConstraintSet.hpp.

Referenced by getJf(), reset(), and iTaSC::Distance::updateJacobian().

e_matrix6 iTaSC::ConstraintSet::m_Jf_inv [protected]

Definition at line 58 of file ConstraintSet.hpp.

Referenced by reset().

Definition at line 54 of file ConstraintSet.hpp.

Referenced by getMaxTimestep(), and iTaSC::CopyPose::getMaxTimestep().

unsigned int iTaSC::ConstraintSet::m_maxIter [protected]

Definition at line 66 of file ConstraintSet.hpp.

Referenced by reset().

unsigned int iTaSC::ConstraintSet::m_nc [protected]

Definition at line 53 of file ConstraintSet.hpp.

Referenced by getNrOfConstraints(), and reset().

Definition at line 62 of file ConstraintSet.hpp.

e_vector6 iTaSC::ConstraintSet::m_S [protected]

Definition at line 57 of file ConstraintSet.hpp.

Referenced by reset().

Definition at line 64 of file ConstraintSet.hpp.

Referenced by substep(), and iTaSC::Distance::updateControlOutput().

e_vector6 iTaSC::ConstraintSet::m_tdelta [protected]

Definition at line 57 of file ConstraintSet.hpp.

Referenced by reset().

e_vector6 iTaSC::ConstraintSet::m_temp [protected]

Definition at line 57 of file ConstraintSet.hpp.

Referenced by reset().

Definition at line 65 of file ConstraintSet.hpp.

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

Definition at line 63 of file ConstraintSet.hpp.

e_matrix6 iTaSC::ConstraintSet::m_U [protected]

Definition at line 58 of file ConstraintSet.hpp.

Referenced by reset().

e_matrix6 iTaSC::ConstraintSet::m_V [protected]

Definition at line 58 of file ConstraintSet.hpp.

Referenced by reset().

e_vector iTaSC::ConstraintSet::m_Wy [protected]

Definition at line 56 of file ConstraintSet.hpp.

Referenced by getWy(), reset(), iTaSC::Distance::setControlParameters(), and setWy().

e_vector iTaSC::ConstraintSet::m_y [protected]

Definition at line 56 of file ConstraintSet.hpp.

Referenced by reset().


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