Blender
V3.3
|
#include <ControlledObject.hpp>
Classes | |
class | JointLockCallback |
Public Member Functions | |
ControlledObject () | |
virtual | ~ControlledObject () |
virtual void | initialize (unsigned int _nq, unsigned int _nc, unsigned int _nee) |
virtual bool | updateJoint (const Timestamp ×tamp, JointLockCallback &callback)=0 |
virtual void | updateControlOutput (const Timestamp ×tamp)=0 |
virtual void | setJointVelocity (const e_vector qdot_in) |
virtual double | getMaxTimestep (double ×tep) |
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 () |
![]() | |
Object (ObjectType _type) | |
virtual | ~Object () |
virtual int | addEndEffector (const std::string &name) |
virtual bool | finalize () |
virtual const KDL::Frame & | getPose (const unsigned int end_effector=0) |
virtual const ObjectType | getType () |
virtual void | updateKinematics (const Timestamp ×tamp)=0 |
virtual void | pushCache (const Timestamp ×tamp)=0 |
virtual void | initCache (Cache *_cache)=0 |
bool | updated () |
void | updated (bool val) |
Protected Attributes | |
e_scalar | m_maxDeltaQ |
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 |
![]() | |
Cache * | m_cache |
KDL::Frame | m_internalPose |
bool | m_updated |
Additional Inherited Members | |
![]() | |
enum | ObjectType { Controlled , UnControlled } |
![]() | |
static WorldObject | world |
![]() | |
virtual void | updateJacobian ()=0 |
Definition at line 22 of file ControlledObject.hpp.
iTaSC::ControlledObject::ControlledObject | ( | ) |
Definition at line 12 of file ControlledObject.cpp.
References e_scalar, and m_maxDeltaQ.
|
virtual |
Definition at line 42 of file ControlledObject.cpp.
|
inlinevirtual |
Definition at line 53 of file ControlledObject.hpp.
References m_ydot.
|
inlinevirtual |
Definition at line 57 of file ControlledObject.hpp.
References m_Cq.
|
virtual |
Definition at line 46 of file ControlledObject.cpp.
Definition at line 52 of file ControlledObject.cpp.
References e_scalar, m_maxDeltaQ, and m_qdot.
|
inlinevirtual |
|
inlinevirtual |
Reimplemented from iTaSC::Object.
Definition at line 64 of file ControlledObject.hpp.
References m_nq.
|
inlinevirtual |
Definition at line 59 of file ControlledObject.hpp.
References m_Wq.
|
inlinevirtual |
Definition at line 62 of file ControlledObject.hpp.
References m_Wy.
|
virtual |
Definition at line 19 of file ControlledObject.cpp.
References e_identity_matrix, e_scalar_vector, e_zero_matrix, e_zero_vector, m_Cq, m_JqArray, m_nc, m_nee, m_nq, m_qdot, m_Wq, m_Wy, and m_ydot.
Referenced by iTaSC::Armature::finalize().
|
pure virtual |
Definition at line 49 of file ControlledObject.hpp.
References m_qdot.
Definition at line 60 of file ControlledObject.hpp.
References m_Wq.
|
pure virtual |
Implemented in iTaSC::Armature.
|
pure virtual |
Implemented in iTaSC::Armature.
|
protected |
Definition at line 26 of file ControlledObject.hpp.
Referenced by iTaSC::Armature::finalize(), getCq(), and initialize().
|
protected |
Definition at line 28 of file ControlledObject.hpp.
Referenced by getJq(), initialize(), and iTaSC::Armature::updateJacobian().
|
protected |
Definition at line 24 of file ControlledObject.hpp.
Referenced by ControlledObject(), and getMaxTimestep().
|
protected |
Definition at line 25 of file ControlledObject.hpp.
Referenced by getNrOfConstraints(), and initialize().
|
protected |
Definition at line 25 of file ControlledObject.hpp.
Referenced by getJq(), iTaSC::Armature::getPose(), initialize(), and iTaSC::Armature::updateJacobian().
|
protected |
Definition at line 25 of file ControlledObject.hpp.
Referenced by getJq(), getNrOfCoordinates(), initialize(), iTaSC::Armature::updateJacobian(), and iTaSC::Armature::updateJoint().
|
protected |
Definition at line 27 of file ControlledObject.hpp.
Referenced by getMaxTimestep(), initialize(), setJointVelocity(), and iTaSC::Armature::updateJoint().
|
protected |
Definition at line 26 of file ControlledObject.hpp.
Referenced by getWq(), initialize(), and setWq().
|
protected |
Definition at line 27 of file ControlledObject.hpp.
Referenced by iTaSC::Armature::finalize(), getWy(), initialize(), iTaSC::Armature::setControlParameter(), and iTaSC::Armature::updateControlOutput().
|
protected |
Definition at line 27 of file ControlledObject.hpp.
Referenced by getControlOutput(), initialize(), and iTaSC::Armature::updateControlOutput().