jrlDelegate::humanoidDynamicRobot Class Reference

Template to implement a non abstract class describing a humanoid robot with dynamics. More...

#include <jrl/dynamics/humanoiddynamicrobot.hh>

Inheritance diagram for jrlDelegate::humanoidDynamicRobot:
Collaboration diagram for jrlDelegate::humanoidDynamicRobot:

Public Member Functions

 humanoidDynamicRobot (CjrlRobotDynamicsObjectFactory *inObjectFactory)
 
 humanoidDynamicRobot (humanoidDynamicRobot *inHDRNA)
 
 humanoidDynamicRobot ()
 
virtual ~humanoidDynamicRobot ()
 Destructor. More...
 
Joints specific to humanoid robots
virtual void waist (CjrlJoint *inWaist)
 Set the pointer to the waist. More...
 
virtual CjrlJointwaist () const
 Get a pointer to the waist. More...
 
virtual void chest (CjrlJoint *inChest)
 Set the pointer to the chest. More...
 
virtual CjrlJointchest () const
 Get a pointer to the chest. More...
 
virtual void leftWrist (CjrlJoint *inLeftWrist)
 Set the pointer to the left wrist joint. More...
 
virtual CjrlJointleftWrist () const
 Get a pointer to the left wrist. More...
 
virtual void rightWrist (CjrlJoint *inRightWrist)
 Set the pointer to the right wrist joint. More...
 
virtual CjrlJointrightWrist () const
 Get a pointer to the right wrist. More...
 
virtual void rightHand (CjrlHand *inRightHand)
 Set the pointer to the right hand. More...
 
virtual CjrlHandrightHand () const
 Get a pointer to the right hand. More...
 
virtual void leftHand (CjrlHand *inLeftHand)
 Set the pointer to the left hand. More...
 
virtual CjrlHandleftHand () const
 Get a pointer to the left hand. More...
 
virtual double getHandClench (CjrlHand *inHand)
 Get the hand clench value. More...
 
virtual bool setHandClench (CjrlHand *inHand, double inClenchingValue)
 Set the hand clench value. More...
 
virtual void leftAnkle (CjrlJoint *inLeftAnkle)
 Set the pointer to the left ankle joint. More...
 
virtual CjrlJointleftAnkle () const
 Get a pointer to the left ankle. More...
 
virtual void rightAnkle (CjrlJoint *inRightAnkle)
 Set the pointer to the right ankle joint. More...
 
virtual CjrlJointrightAnkle () const
 Get a pointer to the right ankle. More...
 
virtual void leftFoot (CjrlFoot *inLeftFoot)
 Set the pointer to the left foot joint. More...
 
virtual CjrlFootleftFoot () const
 Get a pointer to the left foot. More...
 
virtual void rightFoot (CjrlFoot *inRightFoot)
 Set the pointer to the right foot joint. More...
 
virtual CjrlFootrightFoot () const
 Get a pointer to the right foot. More...
 
virtual void gazeJoint (CjrlJoint *inGazeJoint)
 Set gaze joint. More...
 
virtual CjrlJointgazeJoint () const
 Get gaze joint. More...
 
virtual void gaze (const vector3d &inDirection, const vector3d &inOrigin)
 Set the gaze orientation and position in the local frame of the gaze joint. More...
 
virtual const vector3dgazeOrigin () const
 Get a point on the gaze straight line. More...
 
virtual const vector3dgazeDirection () const
 Get the direction of gaze. More...
 
- Public Member Functions inherited from CjrlHumanoidDynamicRobot
virtual ~CjrlHumanoidDynamicRobot ()
 
- Public Member Functions inherited from CjrlDynamicRobot
virtual ~CjrlDynamicRobot ()
 
virtual bool getProperty (const std::string &, std::string &) const
 
virtual ~CjrlDynamicRobot ()
 
virtual bool getProperty (const std::string &, std::string &) const
 
- Public Member Functions inherited from jrlDelegate::dynamicRobot
virtual bool getJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
 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)
 
virtual bool getOrientationJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
 
virtual bool getJacobianCenterOfMass (const CjrlJoint &inStartJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
 
virtual bool getSpecializedInverseKinematics (const CjrlJoint &jointRoot, const CjrlJoint &jointEnd, const matrix4d &jointRootPosition, const matrix4d &jointEndPosition, vectorN &q)
 Compute Speciliazed InverseKinematics between two joints. More...
 
 dynamicRobot (CjrlRobotDynamicsObjectFactory *inObjectFactory)
 
 dynamicRobot (dynamicRobot *inDRNA)
 
 dynamicRobot ()
 
virtual bool initialize ()
 Initialize data-structure necessary to dynamic computations This function should be called after building the tree of joints. More...
 
virtual ~dynamicRobot ()
 Destructor. More...
 
virtual void rootJoint (CjrlJoint &inJoint)
 Set the root joint of the robot. More...
 
virtual CjrlJointrootJoint () const
 Get the root joint of the robot. More...
 
virtual std::vector< CjrlJoint *> jointVector ()
 Get a vector containing all the joints. More...
 
virtual std::vector< CjrlJoint * > jointsBetween (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const
 Get the chain of joints between two joints. More...
 
virtual double upperBoundDof (unsigned int inRankInConfiguration)
 Get the upper bound for ith dof. More...
 
virtual double lowerBoundDof (unsigned int inRankInConfiguration)
 Get the lower bound for ith dof. More...
 
virtual double upperBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)
 Compute the upper bound for ith dof using other configuration values if possible. More...
 
virtual double lowerBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)
 Compute the lower bound for ith dof using other configuration values if possible. More...
 
virtual double upperVelocityBoundDof (unsigned int inRankInConfiguration)
 Get the upper velocity bound for ith dof. More...
 
virtual double lowerVelocityBoundDof (unsigned int inRankInConfiguration)
 Get the lower velocity bound for ith dof. More...
 
virtual double upperTorqueBoundDof (unsigned int inRankInConfiguration)
 Get the upper torque bound for ith dof. More...
 
virtual double lowerTorqueBoundDof (unsigned int inRankInConfiguration)
 Get the lower torque bound for ith dof. More...
 
virtual unsigned int numberDof () const
 Get the number of degrees of freedom of the robot. More...
 
virtual void setJointOrderInConfig (std::vector< CjrlJoint *> inJointVector)
 Set the joint ordering in the configuration vector. More...
 
virtual bool currentConfiguration (const vectorN &inConfig)
 Set the current configuration of the robot. More...
 
virtual const vectorNcurrentConfiguration () const
 Get the current configuration of the robot. More...
 
virtual bool currentVelocity (const vectorN &inVelocity)
 Set the current velocity of the robot. More...
 
virtual const vectorNcurrentVelocity () const
 Get the current velocity of the robot. More...
 
virtual bool currentAcceleration (const vectorN &inAcceleration)
 Set the current acceleration of the robot. More...
 
virtual const vectorNcurrentAcceleration () const
 Get the current acceleration of the robot. More...
 
virtual const matrixNxPcurrentForces () const
 Get the current forces of the robot. More...
 
virtual const matrixNxPcurrentTorques () const
 Get the current torques of the robot. More...
 
virtual const vectorNcurrentJointTorques () const
 Get the current joint torques of the robot. More...
 
virtual bool computeForwardKinematics ()
 Compute forward kinematics. More...
 
virtual bool computeCenterOfMassDynamics ()
 Compute the dynamics of the center of mass. More...
 
virtual const vector3dpositionCenterOfMass () const
 Get the position of the center of mass. More...
 
virtual const vector3dvelocityCenterOfMass ()
 Get the velocity of the center of mass. More...
 
virtual const vector3daccelerationCenterOfMass ()
 Get the acceleration of the center of mass. More...
 
virtual const vector3dlinearMomentumRobot ()
 Get the linear momentum of the robot. More...
 
virtual const vector3dderivativeLinearMomentum ()
 Get the time-derivative of the linear momentum. More...
 
virtual const vector3dangularMomentumRobot ()
 Get the angular momentum of the robot at the center of mass. More...
 
virtual const vector3dderivativeAngularMomentum ()
 Get the time-derivative of the angular momentum at the center of mass. More...
 
virtual double mass () const
 Get the total mass of the robot. More...
 
virtual bool isSupported (const std::string &inProperty)
 Whether the specified property in implemented. More...
 
virtual bool getProperty (const std::string &inProperty, std::string &outValue)
 Get property corresponding to command name. More...
 
virtual bool setProperty (std::string &inProperty, const std::string &inValue)
 Set property corresponding to command name. More...
 
virtual void computeInertiaMatrix ()
 Compute the inertia matrix of the robot according wrt ${\bf q}$. More...
 
virtual const matrixNxPinertiaMatrix () const
 Get the inertia matrix of the robot according wrt ${\bf q}$. More...
 
virtual const std::vector< CjrlJoint * > & getActuatedJoints () const
 Returns the list of actuated joints. More...
 
virtual void setActuatedJoints (std::vector< CjrlJoint *> &lActuatedJoints)
 Specifies the list of actuated joints. More...
 

Zero momentum point

@}

virtual const vector3dzeroMomentumPoint () const
 return the coordinates of the Zero Momentum Point. More...
 
int dynamicsJRLJapan::parseOpenHRPVRMLFile (CjrlHumanoidDynamicRobot &ajrlHumanoidDynamicRobot, std::string &OpenHRPVRMLFile, std::string &MapJointToRankFileName, std::string &SpecificitiesFileName, std::vector< BodyGeometricalData > &VectorOfURLs, bool ReadGeometryInformation)
 

Additional Inherited Members

- Protected Member Functions inherited from jrlDelegate::dynamicRobot
void setDynamicRobot (CjrlDynamicRobot *inDynamicRobot)
 

Detailed Description

Template to implement a non abstract class describing a humanoid robot with dynamics.

This template takes a class implementing the methods of the template CjrlRobotDynamicsObjectConstructor.

Constructor & Destructor Documentation

◆ humanoidDynamicRobot() [1/3]

jrlDelegate::humanoidDynamicRobot::humanoidDynamicRobot ( CjrlRobotDynamicsObjectFactory inObjectFactory)
inline

◆ humanoidDynamicRobot() [2/3]

jrlDelegate::humanoidDynamicRobot::humanoidDynamicRobot ( humanoidDynamicRobot inHDRNA)
inline

◆ humanoidDynamicRobot() [3/3]

jrlDelegate::humanoidDynamicRobot::humanoidDynamicRobot ( )
inline

◆ ~humanoidDynamicRobot()

virtual jrlDelegate::humanoidDynamicRobot::~humanoidDynamicRobot ( )
inlinevirtual

Destructor.

Member Function Documentation

◆ chest() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::chest ( CjrlJoint inChest)
inlinevirtual

Set the pointer to the chest.

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

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::chest().

◆ chest() [2/2]

virtual CjrlJoint* jrlDelegate::humanoidDynamicRobot::chest ( ) const
inlinevirtual

Get a pointer to the chest.

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

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::chest().

◆ gaze()

virtual void jrlDelegate::humanoidDynamicRobot::gaze ( const vector3d inDirection,
const vector3d inOrigin 
)
inlinevirtual

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.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::gaze().

◆ gazeDirection()

virtual const vector3d& jrlDelegate::humanoidDynamicRobot::gazeDirection ( ) const
inlinevirtual

Get the direction of gaze.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::gazeDirection().

◆ gazeJoint() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::gazeJoint ( CjrlJoint inGazeJoint)
inlinevirtual

Set gaze joint.

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

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::gazeJoint().

◆ gazeJoint() [2/2]

virtual CjrlJoint* jrlDelegate::humanoidDynamicRobot::gazeJoint ( ) const
inlinevirtual

Get gaze joint.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::gazeJoint().

◆ gazeOrigin()

virtual const vector3d& jrlDelegate::humanoidDynamicRobot::gazeOrigin ( ) const
inlinevirtual

Get a point on the gaze straight line.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::gazeOrigin().

◆ getHandClench()

virtual double jrlDelegate::humanoidDynamicRobot::getHandClench ( CjrlHand inHand)
inlinevirtual

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)

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::getHandClench().

◆ leftAnkle() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::leftAnkle ( CjrlJoint inLeftAnkle)
inlinevirtual

Set the pointer to the left ankle joint.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::leftAnkle().

◆ leftAnkle() [2/2]

virtual CjrlJoint* jrlDelegate::humanoidDynamicRobot::leftAnkle ( ) const
inlinevirtual

Get a pointer to the left ankle.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::leftAnkle().

◆ leftFoot() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::leftFoot ( CjrlFoot inLeftFoot)
inlinevirtual

Set the pointer to the left foot joint.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::leftFoot().

◆ leftFoot() [2/2]

virtual CjrlFoot* jrlDelegate::humanoidDynamicRobot::leftFoot ( ) const
inlinevirtual

Get a pointer to the left foot.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::leftFoot().

◆ leftHand() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::leftHand ( CjrlHand inLeftHand)
inlinevirtual

Set the pointer to the left hand.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::leftHand().

◆ leftHand() [2/2]

virtual CjrlHand* jrlDelegate::humanoidDynamicRobot::leftHand ( ) const
inlinevirtual

Get a pointer to the left hand.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::leftHand().

◆ leftWrist() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::leftWrist ( CjrlJoint inLeftWrist)
inlinevirtual

Set the pointer to the left wrist joint.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::leftWrist().

◆ leftWrist() [2/2]

virtual CjrlJoint* jrlDelegate::humanoidDynamicRobot::leftWrist ( ) const
inlinevirtual

Get a pointer to the left wrist.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::leftWrist().

◆ rightAnkle() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::rightAnkle ( CjrlJoint inRightAnkle)
inlinevirtual

Set the pointer to the right ankle joint.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::rightAnkle().

◆ rightAnkle() [2/2]

virtual CjrlJoint* jrlDelegate::humanoidDynamicRobot::rightAnkle ( ) const
inlinevirtual

Get a pointer to the right ankle.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::rightAnkle().

◆ rightFoot() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::rightFoot ( CjrlFoot inRightFoot)
inlinevirtual

Set the pointer to the right foot joint.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::rightFoot().

◆ rightFoot() [2/2]

virtual CjrlFoot* jrlDelegate::humanoidDynamicRobot::rightFoot ( ) const
inlinevirtual

Get a pointer to the right foot.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::rightFoot().

◆ rightHand() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::rightHand ( CjrlHand inRightHand)
inlinevirtual

Set the pointer to the right hand.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::rightHand().

◆ rightHand() [2/2]

virtual CjrlHand* jrlDelegate::humanoidDynamicRobot::rightHand ( ) const
inlinevirtual

Get a pointer to the right hand.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::rightHand().

◆ rightWrist() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::rightWrist ( CjrlJoint inRightWrist)
inlinevirtual

Set the pointer to the right wrist joint.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::rightWrist().

◆ rightWrist() [2/2]

virtual CjrlJoint* jrlDelegate::humanoidDynamicRobot::rightWrist ( ) const
inlinevirtual

Get a pointer to the right wrist.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::rightWrist().

◆ setHandClench()

virtual bool jrlDelegate::humanoidDynamicRobot::setHandClench ( CjrlHand inHand,
double  inClenchingValue 
)
inlinevirtual

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

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::setHandClench().

◆ waist() [1/2]

virtual void jrlDelegate::humanoidDynamicRobot::waist ( CjrlJoint inWaist)
inlinevirtual

Set the pointer to the waist.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::waist().

◆ waist() [2/2]

virtual CjrlJoint* jrlDelegate::humanoidDynamicRobot::waist ( ) const
inlinevirtual

Get a pointer to the waist.

Implements CjrlHumanoidDynamicRobot.

References CjrlHumanoidDynamicRobot::waist().

◆ zeroMomentumPoint()

virtual const vector3d& jrlDelegate::humanoidDynamicRobot::zeroMomentumPoint ( ) const
inlinevirtual

return the coordinates of the Zero Momentum Point.

Implements CjrlHumanoidDynamicRobot.

References dynamicsJRLJapan::parseOpenHRPVRMLFile(), and CjrlHumanoidDynamicRobot::zeroMomentumPoint().

Friends And Related Function Documentation

◆ dynamicsJRLJapan::parseOpenHRPVRMLFile

int dynamicsJRLJapan::parseOpenHRPVRMLFile ( CjrlHumanoidDynamicRobot ajrlHumanoidDynamicRobot,
std::string &  OpenHRPVRMLFile,
std::string &  MapJointToRankFileName,
std::string &  SpecificitiesFileName,
std::vector< BodyGeometricalData > &  VectorOfURLs,
bool  ReadGeometryInformation 
)
friend