CjrlHumanoidDynamicRobot Class Referenceabstract

Abstract class describing a humanoid robot with dynamics. More...

#include <abstract-robot-dynamics/humanoid-dynamic-robot.hh>

Inheritance diagram for CjrlHumanoidDynamicRobot:
Collaboration diagram for CjrlHumanoidDynamicRobot:

Public Member Functions

virtual ~CjrlHumanoidDynamicRobot ()
 Destructor. More...
 
Joints specific to humanoid robots
virtual void waist (CjrlJoint *inWaist)=0
 Set the pointer to the waist. More...
 
virtual CjrlJointwaist () const =0
 Get a pointer to the waist. More...
 
virtual void chest (CjrlJoint *inChest)=0
 Set the pointer to the chest. More...
 
virtual CjrlJointchest () 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 CjrlJointleftWrist () 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 CjrlJointrightWrist () 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 CjrlHandrightHand () 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 CjrlHandleftHand () 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 CjrlJointleftAnkle () 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 CjrlJointrightAnkle () 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 CjrlFootleftFoot () 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 CjrlFootrightFoot () const =0
 Get a pointer to the right foot. More...
 
virtual void gazeJoint (CjrlJoint *inGazeJoint)=0
 Set gaze joint. More...
 
virtual CjrlJointgazeJoint () 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 vector3dgazeOrigin () const =0
 Get a point on the gaze straight line. More...
 
virtual const vector3dgazeDirection () const =0
 Get the direction of gaze. More...
 
Zero momentum point
virtual const vector3dzeroMomentumPoint () const =0
 return the coordinates of the Zero Momentum Point. More...
 
- Public Member Functions inherited from CjrlDynamicRobot
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 CjrlJointrootJoint () 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 vectorNcurrentConfiguration () 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 vectorNcurrentVelocity () 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 vectorNcurrentAcceleration () const =0
 Get the current acceleration of the robot. More...
 
virtual const matrixNxPcurrentForces () const =0
 Get the current forces of the robot. More...
 
virtual const matrixNxPcurrentTorques () const =0
 Get the current torques of the robot. More...
 
virtual const vectorNcurrentJointTorques () 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 vector3dpositionCenterOfMass () const =0
 Get the position of the center of mass. More...
 
virtual const vector3dvelocityCenterOfMass ()=0
 Get the velocity of the center of mass. More...
 
virtual const vector3daccelerationCenterOfMass ()=0
 Get the acceleration of the center of mass. More...
 
virtual const vector3dlinearMomentumRobot ()=0
 Get the linear momentum of the robot. More...
 
virtual const vector3dderivativeLinearMomentum ()=0
 Get the time-derivative of the linear momentum. More...
 
virtual const vector3dangularMomentumRobot ()=0
 Get the angular momentum of the robot at the center of mass. More...
 
virtual const vector3dderivativeAngularMomentum ()=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 ${\bf q}$. More...
 
virtual const matrixNxPinertiaMatrix () const =0
 Get the inertia matrix of the robot according wrt ${\bf q}$. 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...
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ~CjrlHumanoidDynamicRobot()

virtual CjrlHumanoidDynamicRobot::~CjrlHumanoidDynamicRobot ( )
inlinevirtual

Destructor.

Member Function Documentation

◆ chest() [1/2]

virtual CjrlJoint* CjrlHumanoidDynamicRobot::chest ( ) const
pure virtual

Get a pointer to the chest.

Note
for some humanoid robots, the waist and the chest are the same joints.

◆ chest() [2/2]

virtual void CjrlHumanoidDynamicRobot::chest ( CjrlJoint inChest)
pure virtual

Set the pointer to the chest.

Note
for some humanoid robots, the waist and the chest are the same joints.

◆ gaze()

virtual void CjrlHumanoidDynamicRobot::gaze ( const vector3d inDirection,
const vector3d inOrigin 
)
pure virtual

Set the gaze orientation and position in the local frame of the gaze joint.

Returns
inOrigin a point on the gaze straight line,
inDirection the direction of the gaze joint.

◆ gazeDirection()

virtual const vector3d& CjrlHumanoidDynamicRobot::gazeDirection ( ) const
pure virtual

Get the direction of gaze.

◆ gazeJoint() [1/2]

virtual CjrlJoint* CjrlHumanoidDynamicRobot::gazeJoint ( ) const
pure virtual

Get gaze joint.

◆ gazeJoint() [2/2]

virtual void CjrlHumanoidDynamicRobot::gazeJoint ( CjrlJoint inGazeJoint)
pure virtual

Set gaze joint.

Note
For most humanoid robots, the gaze joint is the head.

◆ gazeOrigin()

virtual const vector3d& CjrlHumanoidDynamicRobot::gazeOrigin ( ) const
pure virtual

Get a point on the gaze straight line.

◆ getHandClench()

virtual double CjrlHumanoidDynamicRobot::getHandClench ( CjrlHand inHand)
pure virtual

Get the hand clench value.

This is a scalar value ranging between 0 and 1 which describes the hand clench (0 for open and 1 for closed hand)

◆ leftAnkle() [1/2]

virtual CjrlJoint* CjrlHumanoidDynamicRobot::leftAnkle ( ) const
pure virtual

Get a pointer to the left ankle.

◆ leftAnkle() [2/2]

virtual void CjrlHumanoidDynamicRobot::leftAnkle ( CjrlJoint inLefAnkle)
pure virtual

Set the pointer to the left ankle joint.

◆ leftFoot() [1/2]

virtual CjrlFoot* CjrlHumanoidDynamicRobot::leftFoot ( ) const
pure virtual

Get a pointer to the left foot.

◆ leftFoot() [2/2]

virtual void CjrlHumanoidDynamicRobot::leftFoot ( CjrlFoot inLeftFoot)
pure virtual

Set the pointer to the left foot joint.

◆ leftHand() [1/2]

virtual CjrlHand* CjrlHumanoidDynamicRobot::leftHand ( ) const
pure virtual

Get a pointer to the left hand.

◆ leftHand() [2/2]

virtual void CjrlHumanoidDynamicRobot::leftHand ( CjrlHand inLeftHand)
pure virtual

Set the pointer to the left hand.

◆ leftWrist() [1/2]

virtual CjrlJoint* CjrlHumanoidDynamicRobot::leftWrist ( ) const
pure virtual

Get a pointer to the left wrist.

◆ leftWrist() [2/2]

virtual void CjrlHumanoidDynamicRobot::leftWrist ( CjrlJoint inLefWrist)
pure virtual

Set the pointer to the left wrist joint.

◆ rightAnkle() [1/2]

virtual CjrlJoint* CjrlHumanoidDynamicRobot::rightAnkle ( ) const
pure virtual

Get a pointer to the right ankle.

◆ rightAnkle() [2/2]

virtual void CjrlHumanoidDynamicRobot::rightAnkle ( CjrlJoint inRightAnkle)
pure virtual

Set the pointer to the right ankle joint.

◆ rightFoot() [1/2]

virtual CjrlFoot* CjrlHumanoidDynamicRobot::rightFoot ( ) const
pure virtual

Get a pointer to the right foot.

◆ rightFoot() [2/2]

virtual void CjrlHumanoidDynamicRobot::rightFoot ( CjrlFoot inRightFoot)
pure virtual

Set the pointer to the right foot joint.

◆ rightHand() [1/2]

virtual CjrlHand* CjrlHumanoidDynamicRobot::rightHand ( ) const
pure virtual

Get a pointer to the right hand.

◆ rightHand() [2/2]

virtual void CjrlHumanoidDynamicRobot::rightHand ( CjrlHand inRightHand)
pure virtual

Set the pointer to the right hand.

◆ rightWrist() [1/2]

virtual CjrlJoint* CjrlHumanoidDynamicRobot::rightWrist ( ) const
pure virtual

Get a pointer to the right wrist.

◆ rightWrist() [2/2]

virtual void CjrlHumanoidDynamicRobot::rightWrist ( CjrlJoint inRightWrist)
pure virtual

Set the pointer to the right wrist joint.

◆ setHandClench()

virtual bool CjrlHumanoidDynamicRobot::setHandClench ( CjrlHand inHand,
double  inClenchingValue 
)
pure virtual

Set the hand clench value.

This is a scalar value ranging between 0 and 1 which describes the hand clench (0 for open and 1 for closed hand)

Returns
false if parameter 2 is out of range

◆ waist() [1/2]

virtual CjrlJoint* CjrlHumanoidDynamicRobot::waist ( ) const
pure virtual

Get a pointer to the waist.

◆ waist() [2/2]

virtual void CjrlHumanoidDynamicRobot::waist ( CjrlJoint inWaist)
pure virtual

Set the pointer to the waist.

◆ zeroMomentumPoint()

virtual const vector3d& CjrlHumanoidDynamicRobot::zeroMomentumPoint ( ) const
pure virtual

return the coordinates of the Zero Momentum Point.