virtual const matrixNxP & inertiaMatrix() const
Get the inertia matrix of the robot according wrt .
Definition: dynamicrobot.hh:620
jrlDelegate::dynamicRobot CimplDynamicRobot
Definition: robotdynamicsimpl.hh:41
bool convex
Definition: geometricdata.hh:48
virtual double lowerVelocityBoundDof(unsigned int inRankInConfiguration)
Get the lower velocity bound for ith dof.
Definition: dynamicrobot.hh:194
#define DYN_JRL_JAPAN_EXPORT
Definition: dll.hh:37
humanoidDynamicRobot(humanoidDynamicRobot *inHDRNA)
Definition: humanoiddynamicrobot.hh:61
virtual std::vector< CjrlJoint * > jointsBetween(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const
Get the chain of joints between two joints.
Definition: dynamicrobot.hh:133
virtual const vectorN & currentJointTorques() const=0
dynamicsJRLJapan::ObjectFactory CimplObjectFactory
Definition: robotdynamicsimpl.hh:50
std::string FileName
Definition: geometricdata.hh:79
void setDynamicRobot(CjrlDynamicRobot *inDynamicRobot)
Definition: dynamicrobot.hh:51
virtual bool setHandClench(CjrlHand *inHand, double inClenchingValue)
Set the hand clench value.
Definition: humanoiddynamicrobot.hh:216
virtual double upperBoundDof(unsigned int inRankInConfiguration)
Get the upper bound for ith dof.
Definition: dynamicrobot.hh:144
Definition: dynamicbody.hh:42
virtual const vector3d & derivativeAngularMomentum()
Get the time-derivative of the angular momentum at the center of mass.
Definition: dynamicrobot.hh:455
This class represents a robot joint.
Definition: joint.hh:47
virtual bool getPositionJacobian(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
Definition: dynamicrobot.hh:565
Definition: geometricdata.hh:143
virtual bool getJacobianCenterOfMass(const CjrlJoint &inStartJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
virtual bool getJacobian(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
dynamicsJRLJapan::Joint CimplJoint
Definition: robotdynamicsimpl.hh:47
virtual bool currentConfiguration(const vectorN &inConfig)=0
virtual const std::vector< CjrlJoint * > & getActuatedJoints() const
Returns the list of actuated joints.
Definition: dynamicrobot.hh:634
virtual CjrlHand * rightHand() const
Get a pointer to the right hand.
Definition: humanoiddynamicrobot.hh:174
virtual const vector3d & linearMomentumRobot()=0
virtual bool setProperty(std::string &, const std::string &)
Definition: geometricdata.hh:93
virtual void leftHand(CjrlHand *inLeftHand)
Set the pointer to the left hand.
Definition: humanoiddynamicrobot.hh:183
dynamicsJRLJapan::JointTranslation CimplJointTranslation
Definition: robotdynamicsimpl.hh:46
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.
Definition: dynamicrobot.hh:549
virtual void rootJoint(CjrlJoint &inJoint)
Set the root joint of the robot.
Definition: dynamicrobot.hh:101
virtual CjrlJoint * rightWrist() const
Get a pointer to the right wrist.
Definition: humanoiddynamicrobot.hh:156
virtual const vector3d & zeroMomentumPoint() const
return the coordinates of the Zero Momentum Point.
Definition: humanoiddynamicrobot.hh:355
virtual bool getSpecializedInverseKinematics(const CjrlJoint &, const CjrlJoint &, const matrix4d &, const matrix4d &, vectorN &)
virtual const vector3d & gazeDirection() const
Get the direction of gaze.
Definition: humanoiddynamicrobot.hh:338
virtual CjrlHand * leftHand() const
Get a pointer to the left hand.
Definition: humanoiddynamicrobot.hh:192
virtual void setJointOrderInConfig(std::vector< CjrlJoint * > inJointVector)
Set the joint ordering in the configuration vector.
Definition: dynamicrobot.hh:236
jrlMathTools::Matrix3x3< double > matrix3d
virtual double upperBoundDof(unsigned int inRankInConfiguration, const vectorN &inConfig)
Compute the upper bound for ith dof using other configuration values if possible.
Definition: dynamicrobot.hh:165
virtual bool getOrientationJacobian(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
virtual void computeInertiaMatrix()=0
virtual const matrixNxP & currentForces() const
Get the current forces of the robot.
Definition: dynamicrobot.hh:336
virtual CjrlJoint * chest() const
Get a pointer to the chest.
Definition: humanoiddynamicrobot.hh:120
virtual bool currentAcceleration(const vectorN &inAcceleration)=0
virtual bool setProperty(std::string &inProperty, const std::string &inValue)
Set property corresponding to command name.
Definition: dynamicrobot.hh:517
virtual double lowerBoundDof(unsigned int inRankInConfiguration, const vectorN &inConfig)
Compute the lower bound for ith dof using other configuration values if possible.
Definition: dynamicrobot.hh:175
virtual const vector3d & gazeOrigin() const
Get a point on the gaze straight line.
Definition: humanoiddynamicrobot.hh:329
virtual const matrixNxP & currentForces() const=0
Definition: dynamicrobot.hh:39
virtual const vector3d & gazeDirection() const=0
virtual const vector3d & velocityCenterOfMass()
Get the velocity of the center of mass.
Definition: dynamicrobot.hh:410
virtual void leftFoot(CjrlFoot *inLeftFoot)
Set the pointer to the left foot joint.
Definition: humanoiddynamicrobot.hh:261
virtual void chest(CjrlJoint *inChest)=0
virtual const std::vector< CjrlJoint * > & getActuatedJoints() const=0
virtual CjrlFoot * leftFoot() const
Get a pointer to the left foot.
Definition: humanoiddynamicrobot.hh:270
virtual double mass() const=0
virtual void rightAnkle(CjrlJoint *inRightAnkle)=0
virtual void leftAnkle(CjrlJoint *inLefAnkle)=0
virtual void gazeJoint(CjrlJoint *inGazeJoint)
Set gaze joint.
Definition: humanoiddynamicrobot.hh:299
virtual const vector3d & angularMomentumRobot()
Get the angular momentum of the robot at the center of mass.
Definition: dynamicrobot.hh:446
bool colorPerVertex
Definition: geometricdata.hh:47
boost::shared_ptr< CjrlBody > m_privateObj
Definition: dynamicbody.hh:53
double rotation
Definition: geometricdata.hh:85
virtual const vectorN & currentVelocity() const
Get the current velocity of the robot.
Definition: dynamicrobot.hh:298
virtual bool setHandClench(CjrlHand *inHand, double inClenchingValue)=0
virtual double lowerTorqueBoundDof(unsigned int inRankInConfiguration)
Get the lower torque bound for ith dof.
Definition: dynamicrobot.hh:212
virtual void leftWrist(CjrlJoint *inLeftWrist)
Set the pointer to the left wrist joint.
Definition: humanoiddynamicrobot.hh:129
virtual void rightWrist(CjrlJoint *inRightWrist)
Set the pointer to the right wrist joint.
Definition: humanoiddynamicrobot.hh:147
Anchor joint.
Definition: joint.hh:359
virtual void leftWrist(CjrlJoint *inLefWrist)=0
std::vector< int > texCoordIndex
Definition: geometricdata.hh:54
virtual bool computeCenterOfMassDynamics()
Compute the dynamics of the center of mass.
Definition: dynamicrobot.hh:392
virtual void rootJoint(CjrlJoint &inJoint)=0
double creaseAngle
Definition: geometricdata.hh:50
std::vector< int > normalIndex
Definition: geometricdata.hh:51
virtual bool getOrientationJacobian(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
Definition: dynamicrobot.hh:581
virtual CjrlJoint * waist() const
Get a pointer to the waist.
Definition: humanoiddynamicrobot.hh:97
virtual void rightAnkle(CjrlJoint *inRightAnkle)
Set the pointer to the right ankle joint.
Definition: humanoiddynamicrobot.hh:243
dynamicsJRLJapan::Hand CimplHand
Definition: robotdynamicsimpl.hh:49
virtual bool computeForwardKinematics()
Compute forward kinematics.
Definition: dynamicrobot.hh:380
virtual CjrlJoint * leftAnkle() const
Get a pointer to the left ankle.
Definition: humanoiddynamicrobot.hh:234
virtual bool getSpecializedInverseKinematics(const CjrlJoint &jointRoot, const CjrlJoint &jointEnd, const matrix4d &jointRootPosition, const matrix4d &jointEndPosition, vectorN &q)
Compute Speciliazed InverseKinematics between two joints.
Definition: dynamicrobot.hh:679
virtual void waist(CjrlJoint *inWaist)
Set the pointer to the waist.
Definition: humanoiddynamicrobot.hh:87
virtual void gaze(const vector3d &inDirection, const vector3d &inOrigin)
Set the gaze orientation and position in the local frame of the gaze joint.
Definition: humanoiddynamicrobot.hh:319
virtual bool getProperty(const std::string &inProperty, std::string &outValue)
Get property corresponding to command name.
Definition: dynamicrobot.hh:500
virtual void setJointOrderInConfig(std::vector< CjrlJoint * > inJointVector)=0
virtual unsigned int numberDof() const=0
virtual double upperVelocityBoundDof(unsigned int inRankInConfiguration)=0
jrlDelegate::humanoidDynamicRobot CimplHumanoidDynamicRobot
Definition: robotdynamicsimpl.hh:42
virtual double upperBoundDof(unsigned int inRankInConfiguration)=0
virtual bool getPositionJacobian(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
virtual bool initialize()
Initialize data-structure necessary to dynamic computations This function should be called after buil...
Definition: dynamicrobot.hh:75
humanoidDynamicRobot(CjrlRobotDynamicsObjectFactory *inObjectFactory)
Definition: humanoiddynamicrobot.hh:55
virtual bool isSupported(const std::string &)
dynamicsJRLJapan::JointRotation CimplJointRotation
Definition: robotdynamicsimpl.hh:45
virtual const matrixNxP & currentTorques() const
Get the current torques of the robot.
Definition: dynamicrobot.hh:347
boost_ublas::vector< double > vectorN
virtual const vector3d & gazeOrigin() const=0
virtual void rightHand(CjrlHand *inRightHand)
Set the pointer to the right hand.
Definition: humanoiddynamicrobot.hh:165
virtual bool initialize()=0
struct jrlMathTools::Matrix4x4< double > matrix4d
virtual double lowerBoundDof(unsigned int inRankInConfiguration)=0
virtual ~DynamicBody()
Definition: dynamicbody.hh:58
virtual void leftAnkle(CjrlJoint *inLeftAnkle)
Set the pointer to the left ankle joint.
Definition: humanoiddynamicrobot.hh:225
virtual double upperVelocityBoundDof(unsigned int inRankInConfiguration)
Get the upper velocity bound for ith dof.
Definition: dynamicrobot.hh:185
double ambientIntensity
Definition: geometricdata.hh:63
This class implements a body.
Definition: dynamicbody.hh:49
virtual std::vector< CjrlJoint * > jointVector()
Get a vector containing all the joints.
Definition: dynamicrobot.hh:120
boost::shared_ptr< CjrlJoint > m_privateObj
Definition: joint.hh:51
virtual void rightFoot(CjrlFoot *inRightFoot)=0
virtual bool computeForwardKinematics()=0
bool ccw
Definition: geometricdata.hh:45
DYN_JRL_JAPAN_EXPORT int parseOpenHRPVRMLFile(CjrlHumanoidDynamicRobot &ajrlHumanoidDynamicRobot, std::string &OpenHRPVRMLFile, std::string &MapJointToRankFileName, std::string &FileOfSpecificities)
virtual bool getJacobianCenterOfMass(const CjrlJoint &inStartJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
Definition: dynamicrobot.hh:596
virtual void rightFoot(CjrlFoot *inRightFoot)
Set the pointer to the right foot joint.
Definition: humanoiddynamicrobot.hh:279
virtual const vector3d & zeroMomentumPoint() const=0
Free flyer joint.
Definition: joint.hh:332
virtual void leftHand(CjrlHand *inLeftHand)=0
virtual bool getProperty(const std::string &, std::string &) const
virtual const vector3d & angularMomentumRobot()=0
boost_ublas::matrix< double > matrixNxP
virtual ~humanoidDynamicRobot()
Destructor.
Definition: humanoiddynamicrobot.hh:75
virtual const vector3d & derivativeLinearMomentum()=0
virtual void leftFoot(CjrlFoot *inLeftFoot)=0
virtual double getHandClench(CjrlHand *inHand)=0
virtual double getHandClench(CjrlHand *inHand)
Get the hand clench value.
Definition: humanoiddynamicrobot.hh:204
virtual bool computeCenterOfMassDynamics()=0
dynamicsJRLJapan::DynamicBody CimplBody
Definition: robotdynamicsimpl.hh:48
virtual double lowerTorqueBoundDof(unsigned int inRankInConfiguration)=0
virtual void setActuatedJoints(std::vector< CjrlJoint * > &lActuatedJoints)=0
virtual double lowerVelocityBoundDof(unsigned int inRankInConfiguration)=0
virtual const vectorN & currentAcceleration() const
Get the current acceleration of the robot.
Definition: dynamicrobot.hh:324
virtual const vector3d & derivativeLinearMomentum()
Get the time-derivative of the linear momentum.
Definition: dynamicrobot.hh:437
dynamicRobot(dynamicRobot *inDRNA)
Definition: dynamicrobot.hh:63
virtual const vector3d & positionCenterOfMass() const
Get the position of the center of mass.
Definition: dynamicrobot.hh:401
Template to implement a non abstract class describing a humanoid robot with dynamics....
Definition: humanoiddynamicrobot.hh:47
virtual void computeInertiaMatrix()
Compute the inertia matrix of the robot according wrt .
Definition: dynamicrobot.hh:612
dynamicRobot()
Definition: dynamicrobot.hh:67
virtual bool currentVelocity(const vectorN &inVelocity)
Set the current velocity of the robot.
Definition: dynamicrobot.hh:286
std::vector< vector3d > coord
Definition: geometricdata.hh:55
std::vector< int > polygonIndex
Definition: geometricdata.hh:41
virtual const vectorN & currentJointTorques() const
Get the current joint torques of the robot.
Definition: dynamicrobot.hh:358
std::ostream & operator<<(std::ostream &, const Material &)
bool normalPerVertex
Definition: geometricdata.hh:52
virtual CjrlJoint * gazeJoint() const
Get gaze joint.
Definition: humanoiddynamicrobot.hh:308
virtual CjrlFoot * rightFoot() const
Get a pointer to the right foot.
Definition: humanoiddynamicrobot.hh:288
virtual void gaze(const vector3d &inDirection, const vector3d &inOrigin)=0
virtual const vector3d & linearMomentumRobot()
Get the linear momentum of the robot.
Definition: dynamicrobot.hh:428
virtual bool currentConfiguration(const vectorN &inConfig)
Set the current configuration of the robot.
Definition: dynamicrobot.hh:260
dynamicsJRLJapan::JointFreeflyer CimplJointFreeFlyer
Definition: robotdynamicsimpl.hh:43
virtual const vector3d & accelerationCenterOfMass()=0
humanoidDynamicRobot()
Definition: humanoiddynamicrobot.hh:67
virtual double mass() const
Get the total mass of the robot.
Definition: dynamicrobot.hh:464
dynamicsJRLJapan::JointAnchor CimplJointAnchor
Definition: robotdynamicsimpl.hh:44
Definition: geometricdata.hh:82
virtual bool currentAcceleration(const vectorN &inAcceleration)
Set the current acceleration of the robot.
Definition: dynamicrobot.hh:313
virtual void chest(CjrlJoint *inChest)
Set the pointer to the chest.
Definition: humanoiddynamicrobot.hh:109
virtual const matrixNxP & inertiaMatrix() const=0
virtual std::vector< CjrlJoint * > jointsBetween(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const=0
virtual CjrlJoint * rootJoint() const
Get the root joint of the robot.
Definition: dynamicrobot.hh:110
virtual const vectorN & currentConfiguration() const
Get the current configuration of the robot.
Definition: dynamicrobot.hh:271
virtual CjrlJoint * leftWrist() const
Get a pointer to the left wrist.
Definition: humanoiddynamicrobot.hh:138
virtual CjrlJoint * rightAnkle() const
Get a pointer to the right ankle.
Definition: humanoiddynamicrobot.hh:252
virtual const vector3d & positionCenterOfMass() const=0
virtual void waist(CjrlJoint *inWaist)=0
virtual bool currentVelocity(const vectorN &inVelocity)=0
virtual double lowerBoundDof(unsigned int inRankInConfiguration)
Get the lower bound for ith dof.
Definition: dynamicrobot.hh:154
virtual void rightWrist(CjrlJoint *inRightWrist)=0
virtual void gazeJoint(CjrlJoint *inGazeJoint)=0
double shininess
Definition: geometricdata.hh:66
virtual double upperTorqueBoundDof(unsigned int inRankInConfiguration)=0
Translation joint.
Definition: joint.hh:350
virtual std::vector< CjrlJoint * > jointVector()=0
dynamicRobot(CjrlRobotDynamicsObjectFactory *inObjectFactory)
Definition: dynamicrobot.hh:59
virtual ~Joint()
Definition: joint.hh:56
std::vector< polygonIndex > coordIndex
Definition: geometricdata.hh:49
virtual const vector3d & derivativeAngularMomentum()=0
double transparency
Definition: geometricdata.hh:68
virtual unsigned int numberDof() const
Get the number of degrees of freedom of the robot.
Definition: dynamicrobot.hh:222
virtual ~dynamicRobot()
Destructor.
Definition: dynamicrobot.hh:84
virtual void rightHand(CjrlHand *inRightHand)=0
virtual bool isSupported(const std::string &inProperty)
Whether the specified property in implemented.
Definition: dynamicrobot.hh:486
virtual const vector3d & velocityCenterOfMass()=0
bool solid
Definition: geometricdata.hh:53
virtual const vector3d & accelerationCenterOfMass()
Get the acceleration of the center of mass.
Definition: dynamicrobot.hh:419
This class represents a hand. A hand has a central point referenced in the wrist joint frame,...
Definition: hand.hh:42
virtual const matrixNxP & currentTorques() const=0
std::vector< int > colorIndex
Definition: geometricdata.hh:46
virtual void setActuatedJoints(std::vector< CjrlJoint * > &lActuatedJoints)
Specifies the list of actuated joints.
Definition: dynamicrobot.hh:643
Rotation joint.
Definition: joint.hh:341
virtual double upperTorqueBoundDof(unsigned int inRankInConfiguration)
Get the upper torque bound for ith dof.
Definition: dynamicrobot.hh:203