Blender V2.61 - r43446
Classes | Typedefs | Enumerations | Functions | Variables

iTaSC Namespace Reference

Classes

struct  Effector_struct
struct  JointConstraint_struct
struct  Joint_struct
struct  Timestamp
class  Cache
struct  CacheEntry
struct  CacheChannel
struct  CacheBlock
struct  CacheItem
struct  CacheBufferHeader
struct  CacheBuffer
struct  ConstraintSingleValue
struct  ConstraintValues
class  ConstraintSet
class  JointLockCallback
class  CopyPose
class  Distance
class  Range
class  FixedObject
class  MovingFrame
class  Object
class  Scene
class  Solver
class  UncontrolledObject
class  WDLSSolver
class  WorldObject
class  WSDLSSolver

Typedefs

typedef std::vector
< Effector_struct
EffectorList
typedef std::vector
< JointConstraint_struct * > 
JointConstraintList
typedef std::vector< Joint_structJointList
typedef unsigned int CacheTS
typedef bool(* ConstraintCallback )(const Timestamp &timestamp, struct ConstraintValues *const _values, unsigned int _nvalues, void *_param)
typedef bool(* MovingFrameCallback )(const Timestamp &timestamp, const Frame &_current, Frame &_next, void *param)

Enumerations

enum  ID {
  ID_JOINT = 1, ID_JOINT_RX = 2, ID_JOINT_RY = 3, ID_JOINT_RZ = 4,
  ID_JOINT_TX = 2, ID_JOINT_TY = 3, ID_JOINT_TZ = 4
}
enum  ConstraintAction {
  ACT_NONE = 0, ACT_VALUE = 1, ACT_VELOCITY = 2, ACT_TOLERANCE = 4,
  ACT_FEEDBACK = 8, ACT_ALPHA = 16
}

Functions

virtual ~Armature ()
bool addSegment (const std::string &segment_name, const std::string &hook_name, const Joint &joint, const double &q_rest, const Frame &f_tip=F_identity, const Inertia &M=Inertia::Zero())
int addConstraint (const std::string &segment_name, ConstraintCallback _function, void *_param=NULL, bool _freeParam=false, bool _substep=false)
int addLimitConstraint (const std::string &segment_name, unsigned int dof, double _min, double _max)
double getMaxJointChange ()
double getMaxEndEffectorChange ()
bool getSegment (const std::string &segment_name, const unsigned int q_size, const Joint *&p_joint, double &q_rest, double &q, const Frame *&p_tip)
bool getRelativeFrame (Frame &result, const std::string &segment_name, const std::string &base_name=m_root)
virtual void finalize ()
virtual int addEndEffector (const std::string &name)
virtual const FramegetPose (const unsigned int end_effector)
virtual bool updateJoint (const Timestamp &timestamp, JointLockCallback &callback)
virtual void updateKinematics (const Timestamp &timestamp)
virtual void pushCache (const Timestamp &timestamp)
virtual void updateControlOutput (const Timestamp &timestamp)
virtual bool setControlParameter (unsigned int constraintId, unsigned int valueId, ConstraintAction action, double value, double timestep=0.0)
virtual void initCache (Cache *_cache)
virtual bool setJointArray (const KDL::JntArray &joints)
virtual const KDL::JntArraygetJointArray ()
virtual double getArmLength ()
virtual void updateJacobian ()
void setCacheTimestamp (Timestamp &timestamp)
D double unsigned int m_Cf (e_zero_matrix(m_nc, 6))
D double unsigned int m_Wy (e_scalar_vector(m_nc, 1.0))
D double unsigned int m_y (m_nc)
D double unsigned int m_ydot (e_zero_vector(m_nc))
D double unsigned int m_chi (e_zero_vector(6))
D double unsigned int m_S (6)
D double unsigned int m_temp (6)
D double unsigned int m_tdelta (6)
D double unsigned int m_Jf (e_identity_matrix(6, 6))
D double unsigned int m_U (e_identity_matrix(6, 6))
D double unsigned int m_V (e_identity_matrix(6, 6))
D double unsigned int m_B (e_zero_matrix(6, 6))
D double unsigned int m_Jf_inv (e_zero_matrix(6, 6))
D double unsigned int m_internalPose (F_identity)
D double unsigned int m_externalPose (F_identity)
D double unsigned int m_constraintCallback (NULL)
D double unsigned int m_constraintParam (NULL)
D double unsigned int m_toggle (false)
D double unsigned int m_substep (false)
D double unsigned int m_threshold (accuracy)
D double unsigned int m_maxIter (maximum_iterations)
 ControlledObject ()
virtual ~ControlledObject ()
virtual void initialize (unsigned int _nq, unsigned int _nc, unsigned int _nee)
virtual void setJointVelocity (const e_vector qdot_in)
virtual double getMaxTimestep (double &timestep)
virtual bool setControlParameter (unsigned int constraintId, unsigned int valueId, ConstraintAction action, e_scalar value, double timestep=0.0)=0
virtual const e_vector & getControlOutput () const
virtual const e_matrix & getJq (unsigned int ee) const
virtual const e_matrix & getCq () const
virtual e_matrix & getWq ()
virtual void setWq (const e_matrix &Wq_in)
virtual const e_vector & getWy () const
virtual const unsigned int getNrOfCoordinates ()
virtual const unsigned int getNrOfConstraints ()
template<typename MatrixType >
Eigen::Block< MatrixType > project (MatrixType &m, Range r)
template<typename MatrixType >
Eigen::Block< MatrixType > project (MatrixType &m, Range r, Range c)
template<typename Derived >
static int changeBase (Eigen::MatrixBase< Derived > &J, const Frame &T)
m_finalized (false)
m_nframe (0)
 SceneLock (Scene *scene)
virtual ~SceneLock ()
void setRange (Range &range)
virtual void lockJoint (unsigned int q_nr, unsigned int ndof)
virtual void lockJoint (unsigned int q_nr, unsigned int ndof, double *qdot)
static int changeBase (const u_matrix &J_in, const Frame &T, u_matrix &J_out)
static int changeBase (const ublas::matrix_range< u_matrix > &J_in, const Frame &T, ublas::matrix_range< u_matrix > &J_out)
m_epsilon (0.1)
m_nc (0)
m_nq (0)

Variables

__pad0__
static std::string m_root
Tree m_tree
unsigned int m_njoint
unsigned int m_nconstraint
unsigned int m_noutput
unsigned int m_neffector
bool m_finalized
Cachem_cache
double * m_buf
int m_qCCh
CacheTS m_qCTs
int m_yCCh
CacheTS m_yCTs
JntArray m_qKdl
JntArray m_oldqKdl
JntArray m_newqKdl
JntArray m_qdotKdl
Jacobianm_jac
double m_armlength
KDL::TreeJntToJacSolverm_jacsolver
KDL::TreeFkSolverPos_recursivem_fksolver
EffectorList m_effectors
JointConstraintList m_constraints
JointList m_joints
D double accuracy
D double unsigned int maximum_iterations
unsigned int m_nq
unsigned int m_nc
unsigned int m_nee
e_matrix m_Wq
e_matrix m_Cq
e_vector m_Wy
e_vector m_ydot
e_vector m_qdot
std::vector< e_matrix > m_JqArray
const Frame F_identity
Range m_qrange

Typedef Documentation

typedef unsigned int iTaSC::CacheTS

Definition at line 32 of file Cache.hpp.

typedef bool(* iTaSC::ConstraintCallback)(const Timestamp &timestamp, struct ConstraintValues *const _values, unsigned int _nvalues, void *_param)

Definition at line 49 of file ConstraintSet.hpp.

typedef std::vector<Effector_struct> iTaSC::EffectorList

Definition at line 61 of file Armature.hpp.

Definition at line 85 of file Armature.hpp.

typedef std::vector<Joint_struct> iTaSC::JointList

Definition at line 99 of file Armature.hpp.

typedef bool(* iTaSC::MovingFrameCallback)(const Timestamp &timestamp, const Frame &_current, Frame &_next, void *param)

Definition at line 17 of file MovingFrame.hpp.


Enumeration Type Documentation

Enumerator:
ACT_NONE 
ACT_VALUE 
ACT_VELOCITY 
ACT_TOLERANCE 
ACT_FEEDBACK 
ACT_ALPHA 

Definition at line 18 of file ConstraintSet.hpp.

enum iTaSC::ID
Enumerator:
ID_JOINT 
ID_JOINT_RX 
ID_JOINT_RY 
ID_JOINT_RZ 
ID_JOINT_TX 
ID_JOINT_TY 
ID_JOINT_TZ 

Definition at line 63 of file Armature.hpp.


Function Documentation

int iTaSC::addConstraint ( const std::string &  segment_name,
ConstraintCallback  _function,
void *  _param = NULL,
bool  _freeParam = false,
bool  _substep = false 
)
virtual int iTaSC::addEndEffector ( const std::string &  name) [virtual]
int iTaSC::Armature::addLimitConstraint ( const std::string &  segment_name,
unsigned int  dof,
double  _min,
double  _max 
)
bool iTaSC::addSegment ( const std::string &  segment_name,
const std::string &  hook_name,
const Joint &  joint,
const double &  q_rest,
const Frame &  f_tip = F_identity,
const Inertia &  M = Inertia::Zero() 
)
static int iTaSC::changeBase ( const u_matrix &  J_in,
const Frame &  T,
u_matrix &  J_out 
) [inline, static]

Definition at line 48 of file ublas_types.hpp.

References i.

static int iTaSC::changeBase ( const ublas::matrix_range< u_matrix > &  J_in,
const Frame &  T,
ublas::matrix_range< u_matrix > &  J_out 
) [inline, static]

Definition at line 64 of file ublas_types.hpp.

References i.

template<typename Derived >
static int iTaSC::changeBase ( Eigen::MatrixBase< Derived > &  J,
const Frame &  T 
) [inline, static]

Definition at line 67 of file eigen_types.hpp.

References e_scalar, and i.

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

iTaSC::ControlledObject::ControlledObject ( )

Definition at line 15 of file ControlledObject.cpp.

References e_scalar.

Referenced by iTaSC::Scene::addObject(), and iTaSC::Scene::update().

virtual void iTaSC::finalize ( ) [virtual]
virtual double iTaSC::getArmLength ( ) [virtual]

Definition at line 50 of file Armature.hpp.

virtual const e_vector& iTaSC::getControlOutput ( ) const [virtual]

Definition at line 54 of file ControlledObject.hpp.

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

virtual const e_matrix& iTaSC::getCq ( ) const [virtual]

Definition at line 58 of file ControlledObject.hpp.

References m_Wq.

const KDL::JntArray & iTaSC::Armature::getJointArray ( ) [virtual]

Definition at line 435 of file Armature.cpp.

References m_qKdl.

const e_matrix & iTaSC::ControlledObject::getJq ( unsigned int  ee) const [virtual]

Definition at line 49 of file ControlledObject.cpp.

References assert, m_JqArray, m_nee, and m_nq.

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

double iTaSC::Armature::getMaxEndEffectorChange ( )
double iTaSC::Armature::getMaxJointChange ( )

Definition at line 264 of file Armature.cpp.

References fabs(), i, m_finalized, m_njoint, m_oldqKdl, and m_qKdl.

virtual double iTaSC::getMaxTimestep ( double &  timestep) [virtual]
virtual const unsigned int iTaSC::getNrOfConstraints ( ) [virtual]

Definition at line 66 of file ControlledObject.hpp.

virtual const unsigned int iTaSC::getNrOfCoordinates ( ) [virtual]

Definition at line 65 of file ControlledObject.hpp.

References m_nc.

virtual const Frame& iTaSC::getPose ( const unsigned int  end_effector) [virtual]
bool iTaSC::Armature::getRelativeFrame ( Frame &  result,
const std::string &  segment_name,
const std::string &  base_name = m_root 
)
bool iTaSC::getSegment ( const std::string &  segment_name,
const unsigned int  q_size,
const Joint *&  p_joint,
double &  q_rest,
double &  q,
const Frame *&  p_tip 
)
virtual e_matrix& iTaSC::getWq ( ) [virtual]

Definition at line 60 of file ControlledObject.hpp.

References m_Wq.

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

virtual const e_vector& iTaSC::getWy ( ) const [virtual]

Definition at line 63 of file ControlledObject.hpp.

References m_nq.

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

virtual void iTaSC::initCache ( Cache _cache) [virtual]
virtual void iTaSC::initialize ( unsigned int  _nq,
unsigned int  _nc,
unsigned int  _nee 
) [virtual]
virtual void iTaSC::lockJoint ( unsigned int  q_nr,
unsigned int  ndof,
double *  qdot 
) [virtual]

Definition at line 40 of file itasc/scene.cpp.

References i, m_qrange, project(), and iTaSC::Range::start.

virtual void iTaSC::lockJoint ( unsigned int  q_nr,
unsigned int  ndof 
) [virtual]

Definition at line 34 of file itasc/scene.cpp.

References m_qrange, project(), and iTaSC::Range::start.

D double unsigned int iTaSC::m_B ( e_zero_matrix(6, 6)  )
D double unsigned int iTaSC::m_Cf ( e_zero_matrix(m_nc, 6)  )
D double unsigned int iTaSC::m_chi ( e_zero_vector(6)  )
D double unsigned int iTaSC::m_constraintCallback ( NULL  )
D double unsigned int iTaSC::m_constraintParam ( NULL  )
D iTaSC::m_epsilon ( 0.  1)

Definition at line 17 of file WDLSSolver.cpp.

D double unsigned int iTaSC::m_externalPose ( F_identity  )
D iTaSC::m_finalized ( false  )
D double unsigned int iTaSC::m_internalPose ( F_identity  )
D double unsigned int iTaSC::m_Jf ( e_identity_matrix(6, 6)  )
D double unsigned int iTaSC::m_Jf_inv ( e_zero_matrix(6, 6)  )
D double unsigned int iTaSC::m_maxIter ( maximum_iterations  )

Definition at line 29 of file ConstraintSet.cpp.

References e_scalar.

D iTaSC::m_nc ( )
D iTaSC::m_nframe ( )

Definition at line 18 of file FixedObject.cpp.

D iTaSC::m_nq ( )

Definition at line 19 of file WSDLSSolver.cpp.

D double unsigned int iTaSC::m_S ( )
D double unsigned int iTaSC::m_substep ( false  )
D double unsigned int iTaSC::m_tdelta ( )
D double unsigned int iTaSC::m_temp ( )
D double unsigned int iTaSC::m_threshold ( accuracy  )
D double unsigned int iTaSC::m_toggle ( false  )
D double unsigned int iTaSC::m_U ( e_identity_matrix(6, 6)  )
D double unsigned int iTaSC::m_V ( e_identity_matrix(6, 6)  )
D double unsigned int iTaSC::m_Wy ( e_scalar_vector(m_nc, 1.0)  )
D double unsigned int iTaSC::m_y ( m_nc  )

Referenced by SCA_MouseSensor::setY().

D double unsigned int iTaSC::m_ydot ( e_zero_vector(m_nc)  )
template<typename MatrixType >
Eigen::Block<MatrixType> iTaSC::project ( MatrixType &  m,
Range  r 
) [inline]
template<typename MatrixType >
Eigen::Block<MatrixType> iTaSC::project ( MatrixType &  m,
Range  r,
Range  c 
) [inline]

Definition at line 62 of file eigen_types.hpp.

References iTaSC::Range::count, and iTaSC::Range::start.

virtual void iTaSC::pushCache ( const Timestamp &  timestamp) [virtual]
iTaSC::SceneLock ( Scene scene)

Definition at line 25 of file itasc/scene.cpp.

void iTaSC::setCacheTimestamp ( Timestamp &  timestamp) [inline]

Definition at line 51 of file Cache.hpp.

References iTaSC::Timestamp::cacheTimestamp, and iTaSC::Timestamp::realTimestamp.

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

virtual bool iTaSC::setControlParameter ( unsigned int  constraintId,
unsigned int  valueId,
ConstraintAction  action,
e_scalar  value,
double  timestep = 0.0 
) [pure virtual]
virtual bool iTaSC::setControlParameter ( unsigned int  constraintId,
unsigned int  valueId,
ConstraintAction  action,
double  value,
double  timestep = 0.0 
) [virtual]
bool iTaSC::Armature::setJointArray ( const KDL::JntArray joints) [virtual]

Definition at line 424 of file Armature.cpp.

References m_finalized, m_qKdl, KDL::JntArray::rows(), and updateJacobian().

virtual void iTaSC::setJointVelocity ( const e_vector  qdot_in) [virtual]

Definition at line 50 of file ControlledObject.hpp.

void iTaSC::setRange ( Range &  range)

Definition at line 29 of file itasc/scene.cpp.

References m_qrange.

virtual void iTaSC::setWq ( const e_matrix &  Wq_in) [virtual]

Definition at line 61 of file ControlledObject.hpp.

References m_Wy.

void iTaSC::updateControlOutput ( const Timestamp &  timestamp) [virtual]

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

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

Referenced by setJointArray().

bool iTaSC::updateJoint ( const Timestamp &  timestamp,
JointLockCallback &  callback 
) [virtual]
virtual void iTaSC::updateKinematics ( const Timestamp &  timestamp) [virtual]
iTaSC::Armature::~Armature ( ) [virtual]

Definition at line 48 of file Armature.cpp.

References m_buf, m_constraints, m_fksolver, m_jac, m_jacsolver, and NULL.

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

Definition at line 45 of file ControlledObject.cpp.

virtual iTaSC::~SceneLock ( ) [virtual]

Definition at line 27 of file itasc/scene.cpp.


Variable Documentation

Definition at line 20 of file Armature.cpp.

D double iTaSC::accuracy

Definition at line 123 of file Armature.hpp.

double* iTaSC::m_buf

Definition at line 113 of file Armature.hpp.

Referenced by ~Armature().

Definition at line 112 of file Armature.hpp.

Definition at line 128 of file Armature.hpp.

Referenced by ~Armature().

e_matrix iTaSC::m_Cq

Definition at line 27 of file ControlledObject.hpp.

Definition at line 127 of file Armature.hpp.

Referenced by getMaxEndEffectorChange().

Definition at line 126 of file Armature.hpp.

Referenced by iTaSC::Distance::Distance(), getRelativeFrame(), and ~Armature().

Definition at line 125 of file Armature.hpp.

Referenced by iTaSC::Distance::Distance(), and ~Armature().

Definition at line 129 of file Armature.hpp.

Referenced by addLimitConstraint(), and updateJoint().

std::vector<e_matrix> iTaSC::m_JqArray

Definition at line 29 of file ControlledObject.hpp.

Referenced by getJq().

unsigned int iTaSC::m_nc

Definition at line 26 of file ControlledObject.hpp.

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

unsigned int iTaSC::m_nconstraint

Definition at line 108 of file Armature.hpp.

unsigned int iTaSC::m_nee

Definition at line 26 of file ControlledObject.hpp.

Referenced by getJq().

unsigned int iTaSC::m_neffector

Definition at line 110 of file Armature.hpp.

Referenced by getMaxEndEffectorChange().

Definition at line 120 of file Armature.hpp.

Referenced by updateJoint().

unsigned int iTaSC::m_njoint

Definition at line 107 of file Armature.hpp.

Referenced by getMaxJointChange().

unsigned int iTaSC::m_noutput

Definition at line 109 of file Armature.hpp.

unsigned int iTaSC::m_nq

Definition at line 26 of file ControlledObject.hpp.

Referenced by getJq(), getWy(), and updateJoint().

Definition at line 119 of file Armature.hpp.

Referenced by getMaxJointChange().

Definition at line 114 of file Armature.hpp.

Definition at line 115 of file Armature.hpp.

e_vector iTaSC::m_qdot

Definition at line 28 of file ControlledObject.hpp.

Referenced by updateJoint().

Definition at line 121 of file Armature.hpp.

Referenced by updateJoint().

Definition at line 22 of file itasc/scene.cpp.

Referenced by lockJoint(), and setRange().

std::string iTaSC::m_root [static]

Definition at line 106 of file Armature.hpp.

Referenced by addLimitConstraint().

e_matrix iTaSC::m_Wq

Definition at line 27 of file ControlledObject.hpp.

Referenced by getCq(), and getWq().

e_vector iTaSC::m_Wy

Definition at line 116 of file Armature.hpp.

Definition at line 117 of file Armature.hpp.

e_vector iTaSC::m_ydot

Definition at line 28 of file ControlledObject.hpp.

D double unsigned int iTaSC::maximum_iterations

Definition at line 17 of file ConstraintSet.cpp.

Referenced by iTaSC::ConstraintSet::reset().