virtual ~CjrlHumanoidDynamicRobot ()
Destructor. More...
virtual void waist (CjrlJoint *inWaist)=0
Set the pointer to the waist. More...
virtual CjrlJoint * waist () const =0
Get a pointer to the waist. More...
virtual void chest (CjrlJoint *inChest)=0
Set the pointer to the chest. More...
virtual CjrlJoint * chest () const =0
Get a pointer to the chest. More...
virtual void leftWrist (CjrlJoint *inLefWrist)=0
Set the pointer to the left wrist joint. More...
virtual CjrlJoint * leftWrist () const =0
Get a pointer to the left wrist. More...
virtual void rightWrist (CjrlJoint *inRightWrist)=0
Set the pointer to the right wrist joint. More...
virtual CjrlJoint * rightWrist () const =0
Get a pointer to the right wrist. More...
virtual void rightHand (CjrlHand *inRightHand)=0
Set the pointer to the right hand. More...
virtual CjrlHand * rightHand () const =0
Get a pointer to the right hand. More...
virtual void leftHand (CjrlHand *inLeftHand)=0
Set the pointer to the left hand. More...
virtual CjrlHand * leftHand () const =0
Get a pointer to the left hand. More...
virtual double getHandClench (CjrlHand *inHand)=0
Get the hand clench value. More...
virtual bool setHandClench (CjrlHand *inHand, double inClenchingValue)=0
Set the hand clench value. More...
virtual void leftAnkle (CjrlJoint *inLefAnkle)=0
Set the pointer to the left ankle joint. More...
virtual CjrlJoint * leftAnkle () const =0
Get a pointer to the left ankle. More...
virtual void rightAnkle (CjrlJoint *inRightAnkle)=0
Set the pointer to the right ankle joint. More...
virtual CjrlJoint * rightAnkle () const =0
Get a pointer to the right ankle. More...
virtual void leftFoot (CjrlFoot *inLeftFoot)=0
Set the pointer to the left foot joint. More...
virtual CjrlFoot * leftFoot () const =0
Get a pointer to the left foot. More...
virtual void rightFoot (CjrlFoot *inRightFoot)=0
Set the pointer to the right foot joint. More...
virtual CjrlFoot * rightFoot () const =0
Get a pointer to the right foot. More...
virtual void gazeJoint (CjrlJoint *inGazeJoint)=0
Set gaze joint. More...
virtual CjrlJoint * gazeJoint () const =0
Get gaze joint. More...
virtual void gaze (const vector3d &inDirection, const vector3d &inOrigin)=0
Set the gaze orientation and position in the local frame of the gaze joint. More...
virtual const vector3d & gazeOrigin () const =0
Get a point on the gaze straight line. More...
virtual const vector3d & gazeDirection () const =0
Get the direction of gaze. More...
virtual const vector3d & zeroMomentumPoint () const =0
return the coordinates of the Zero Momentum Point. More...
virtual bool getJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
Compute and get position and orientation jacobian. More...
virtual bool getPositionJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
virtual bool getOrientationJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
virtual bool getJacobianCenterOfMass (const CjrlJoint &inStartJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
virtual bool getSpecializedInverseKinematics (const CjrlJoint &, const CjrlJoint &, const matrix4d &, const matrix4d &, vectorN &)
Compute Speciliazed InverseKinematics between two joints. More...
virtual bool initialize ()=0
Initialize data-structure necessary to dynamic computations This function should be called after building the tree of joints. More...
virtual ~CjrlDynamicRobot ()
Destructor. More...
virtual void rootJoint (CjrlJoint &inJoint)=0
Set the root joint of the robot. More...
virtual CjrlJoint * rootJoint () const =0
Get the root joint of the robot. More...
virtual std::vector< CjrlJoint * > jointVector ()=0
Get a vector containing all the joints. More...
virtual std::vector< CjrlJoint * > jointsBetween (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const =0
Get the chain of joints between two joints. More...
virtual double upperBoundDof (unsigned int inRankInConfiguration)=0
Get the upper bound for ith dof. More...
virtual double lowerBoundDof (unsigned int inRankInConfiguration)=0
Get the lower bound for ith dof. More...
virtual double upperBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)=0
Compute the upper bound for ith dof using other configuration values if possible. More...
virtual double lowerBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)=0
Compute the lower bound for ith dof using other configuration values if possible. More...
virtual double upperVelocityBoundDof (unsigned int inRankInConfiguration)=0
Get the upper velocity bound for ith dof. More...
virtual double lowerVelocityBoundDof (unsigned int inRankInConfiguration)=0
Get the lower velocity bound for ith dof. More...
virtual double upperTorqueBoundDof (unsigned int inRankInConfiguration)=0
Get the upper torque bound for ith dof. More...
virtual double lowerTorqueBoundDof (unsigned int inRankInConfiguration)=0
Get the lower torque bound for ith dof. More...
virtual unsigned int numberDof () const =0
Get the number of degrees of freedom of the robot. More...
virtual void setJointOrderInConfig (std::vector< CjrlJoint * > inJointVector)=0
Set the joint ordering in the configuration vector. More...
virtual bool currentConfiguration (const vectorN &inConfig)=0
Set the current configuration of the robot. More...
virtual const vectorN & currentConfiguration () const =0
Get the current configuration of the robot. More...
virtual bool currentVelocity (const vectorN &inVelocity)=0
Set the current velocity of the robot. More...
virtual const vectorN & currentVelocity () const =0
Get the current velocity of the robot. More...
virtual bool currentAcceleration (const vectorN &inAcceleration)=0
Set the current acceleration of the robot. More...
virtual const vectorN & currentAcceleration () const =0
Get the current acceleration of the robot. More...
virtual const matrixNxP & currentForces () const =0
Get the current forces of the robot. More...
virtual const matrixNxP & currentTorques () const =0
Get the current torques of the robot. More...
virtual const vectorN & currentJointTorques () const =0
Get the current joint torques of the robot. More...
virtual bool computeForwardKinematics ()=0
Compute forward kinematics. More...
virtual bool computeCenterOfMassDynamics ()=0
Compute the dynamics of the center of mass. More...
virtual const vector3d & positionCenterOfMass () const =0
Get the position of the center of mass. More...
virtual const vector3d & velocityCenterOfMass ()=0
Get the velocity of the center of mass. More...
virtual const vector3d & accelerationCenterOfMass ()=0
Get the acceleration of the center of mass. More...
virtual const vector3d & linearMomentumRobot ()=0
Get the linear momentum of the robot. More...
virtual const vector3d & derivativeLinearMomentum ()=0
Get the time-derivative of the linear momentum. More...
virtual const vector3d & angularMomentumRobot ()=0
Get the angular momentum of the robot at the center of mass. More...
virtual const vector3d & derivativeAngularMomentum ()=0
Get the time-derivative of the angular momentum at the center of mass. More...
virtual double mass () const =0
Get the total mass of the robot. More...
virtual bool isSupported (const std::string &)
Whether the specified property in implemented. More...
virtual bool getProperty (const std::string &, std::string &) const
Get property corresponding to command name. More...
virtual bool setProperty (std::string &, const std::string &)
Set property corresponding to command name. More...
virtual void computeInertiaMatrix ()=0
Compute the inertia matrix of the robot according wrt . More...
virtual const matrixNxP & inertiaMatrix () const =0
Get the inertia matrix of the robot according wrt . More...
virtual const std::vector< CjrlJoint * > & getActuatedJoints () const =0
Returns the list of actuated joints. More...
virtual void setActuatedJoints (std::vector< CjrlJoint * > &lActuatedJoints)=0
Specifies the list of actuated joints. More...
Abstract class describing a humanoid robot with dynamics.
This class derives for CjrlDynamicRobot and instantiate properties specific to humanoid robots.
it provides pointers to the feet and hand joints,
it provides pointers to the joint corresponding to the gaze,
it computes the Zero Momentum Point.
Definition This class describes a humanoid robot as a kinematic chain with two arms, two feet and a vision sensor. The axis of the sensor is called gaze. Hands are linked to the robot by arms connected at the chest joint. Feet are linked to the robot by legs connected at the waist joint. No access to the joints composing the limbs are provided by this class. See class CjrlHumDynRobotType2 for this type of information.