Template to implement a non abstract class describing a humanoid robot with dynamics. More...
#include <jrl/dynamics/humanoiddynamicrobot.hh>
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 CjrlJoint * | waist () const |
Get a pointer to the waist. More... | |
virtual void | chest (CjrlJoint *inChest) |
Set the pointer to the chest. More... | |
virtual CjrlJoint * | chest () const |
Get a pointer to the chest. More... | |
virtual void | leftWrist (CjrlJoint *inLeftWrist) |
Set the pointer to the left wrist joint. More... | |
virtual CjrlJoint * | leftWrist () const |
Get a pointer to the left wrist. More... | |
virtual void | rightWrist (CjrlJoint *inRightWrist) |
Set the pointer to the right wrist joint. More... | |
virtual CjrlJoint * | rightWrist () const |
Get a pointer to the right wrist. More... | |
virtual void | rightHand (CjrlHand *inRightHand) |
Set the pointer to the right hand. More... | |
virtual CjrlHand * | rightHand () const |
Get a pointer to the right hand. More... | |
virtual void | leftHand (CjrlHand *inLeftHand) |
Set the pointer to the left hand. More... | |
virtual CjrlHand * | leftHand () 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 CjrlJoint * | leftAnkle () const |
Get a pointer to the left ankle. More... | |
virtual void | rightAnkle (CjrlJoint *inRightAnkle) |
Set the pointer to the right ankle joint. More... | |
virtual CjrlJoint * | rightAnkle () const |
Get a pointer to the right ankle. More... | |
virtual void | leftFoot (CjrlFoot *inLeftFoot) |
Set the pointer to the left foot joint. More... | |
virtual CjrlFoot * | leftFoot () const |
Get a pointer to the left foot. More... | |
virtual void | rightFoot (CjrlFoot *inRightFoot) |
Set the pointer to the right foot joint. More... | |
virtual CjrlFoot * | rightFoot () const |
Get a pointer to the right foot. More... | |
virtual void | gazeJoint (CjrlJoint *inGazeJoint) |
Set gaze joint. More... | |
virtual CjrlJoint * | gazeJoint () 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 vector3d & | gazeOrigin () const |
Get a point on the gaze straight line. More... | |
virtual const vector3d & | gazeDirection () const |
Get the direction of gaze. More... | |
![]() | |
virtual | ~CjrlHumanoidDynamicRobot () |
![]() | |
virtual | ~CjrlDynamicRobot () |
virtual bool | getProperty (const std::string &, std::string &) const |
virtual | ~CjrlDynamicRobot () |
virtual bool | getProperty (const std::string &, std::string &) const |
![]() | |
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 CjrlJoint * | rootJoint () 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 vectorN & | currentConfiguration () 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 vectorN & | currentVelocity () 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 vectorN & | currentAcceleration () const |
Get the current acceleration of the robot. More... | |
virtual const matrixNxP & | currentForces () const |
Get the current forces of the robot. More... | |
virtual const matrixNxP & | currentTorques () const |
Get the current torques of the robot. More... | |
virtual const vectorN & | currentJointTorques () 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 vector3d & | positionCenterOfMass () const |
Get the position of the center of mass. More... | |
virtual const vector3d & | velocityCenterOfMass () |
Get the velocity of the center of mass. More... | |
virtual const vector3d & | accelerationCenterOfMass () |
Get the acceleration of the center of mass. More... | |
virtual const vector3d & | linearMomentumRobot () |
Get the linear momentum of the robot. More... | |
virtual const vector3d & | derivativeLinearMomentum () |
Get the time-derivative of the linear momentum. More... | |
virtual const vector3d & | angularMomentumRobot () |
Get the angular momentum of the robot at the center of mass. More... | |
virtual const vector3d & | derivativeAngularMomentum () |
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 ![]() | |
virtual const matrixNxP & | inertiaMatrix () const |
Get the inertia matrix of the robot according wrt ![]() | |
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 vector3d & | zeroMomentumPoint () 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 | |
![]() | |
void | setDynamicRobot (CjrlDynamicRobot *inDynamicRobot) |
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.
|
inline |
References jrlDelegate::dynamicRobot::setDynamicRobot().
|
inline |
References jrlDelegate::dynamicRobot::setDynamicRobot().
|
inline |
References jrlDelegate::dynamicRobot::setDynamicRobot().
|
inlinevirtual |
Destructor.
|
inlinevirtual |
Set the pointer to the chest.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::chest().
|
inlinevirtual |
Get a pointer to the chest.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::chest().
|
inlinevirtual |
Set the gaze orientation and position in the local frame of the gaze joint.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::gaze().
|
inlinevirtual |
Get the direction of gaze.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::gazeDirection().
|
inlinevirtual |
Set gaze joint.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::gazeJoint().
|
inlinevirtual |
Get gaze joint.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::gazeJoint().
|
inlinevirtual |
Get a point on the gaze straight line.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::gazeOrigin().
|
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().
|
inlinevirtual |
Set the pointer to the left ankle joint.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::leftAnkle().
|
inlinevirtual |
Get a pointer to the left ankle.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::leftAnkle().
|
inlinevirtual |
Set the pointer to the left foot joint.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::leftFoot().
|
inlinevirtual |
Get a pointer to the left foot.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::leftFoot().
|
inlinevirtual |
Set the pointer to the left hand.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::leftHand().
|
inlinevirtual |
Get a pointer to the left hand.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::leftHand().
|
inlinevirtual |
Set the pointer to the left wrist joint.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::leftWrist().
|
inlinevirtual |
Get a pointer to the left wrist.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::leftWrist().
|
inlinevirtual |
Set the pointer to the right ankle joint.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::rightAnkle().
|
inlinevirtual |
Get a pointer to the right ankle.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::rightAnkle().
|
inlinevirtual |
Set the pointer to the right foot joint.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::rightFoot().
|
inlinevirtual |
Get a pointer to the right foot.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::rightFoot().
|
inlinevirtual |
Set the pointer to the right hand.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::rightHand().
|
inlinevirtual |
Get a pointer to the right hand.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::rightHand().
|
inlinevirtual |
Set the pointer to the right wrist joint.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::rightWrist().
|
inlinevirtual |
Get a pointer to the right wrist.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::rightWrist().
|
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)
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::setHandClench().
|
inlinevirtual |
Set the pointer to the waist.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::waist().
|
inlinevirtual |
Get a pointer to the waist.
Implements CjrlHumanoidDynamicRobot.
References CjrlHumanoidDynamicRobot::waist().
|
inlinevirtual |
return the coordinates of the Zero Momentum Point.
Implements CjrlHumanoidDynamicRobot.
References dynamicsJRLJapan::parseOpenHRPVRMLFile(), and CjrlHumanoidDynamicRobot::zeroMomentumPoint().
|
friend |