virtual CjrlJoint * rootJoint() const =0
Get the root joint of the robot.
virtual const matrixNxP & jacobianJointWrtConfig() const =0
Get the Jacobian matrix of the joint position and orientation wrt the robot configuration.
virtual ~CjrlDynamicRobot()
Destructor.
Definition: dynamic-robot.hh:72
This class represents a robot joint.
Definition: joint.hh:75
virtual CjrlJoint * createJointTranslation(const matrix4d &inInitialPosition)=0
Construct and return a pointer to a translation joint.
virtual const vectorN & currentJointTorques() const =0
Get the current joint torques of the robot.
virtual double lowerVelocityBound(unsigned int inDofRank) const =0
Get the lower velocity bound of a given degree of freedom of the joint.
virtual CjrlFoot * rightFoot() const =0
Get a pointer to the right foot.
virtual void getCenter(vector3d &outCenter) const =0
Get the center of the hand.
virtual CjrlHand * leftHand() const =0
Get a pointer to the left hand.
Abstract class that instantiates a robot with dynamic properties.
Definition: dynamic-robot.hh:61
virtual double upperVelocityBound(unsigned int inDofRank) const =0
Get the upper veocity bound of a given degree of freedom of the joint.
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
Compute and get position and orientation jacobian.
virtual void getAnklePositionInLocalFrame(vector3d &outCoordinates) const =0
Get position of the ankle in the foot local coordinate frame.
virtual void getPalmNormal(vector3d &outPalmNormal) const =0
Get palm normal.
virtual CjrlJoint * leftAnkle() const =0
Get a pointer to the left ankle.
virtual CjrlJoint * associatedWrist() const =0
Get the wrist joint to which the hand is attached.
virtual CjrlFoot * createFoot(CjrlJoint *inAnkle)=0
Construct and return a pointer to a foot.
virtual const vector3d & linearMomentumRobot()=0
Get the linear momentum of the robot.
virtual bool setProperty(std::string &, const std::string &)
Set property corresponding to command name.
Definition: dynamic-robot.hh:386
const vector3d & rotationVelocity() const
Get the rotation velocity vector.
Definition: rigid-velocity.hh:56
This class represents the velocity of a rigid body.
Definition: rigid-velocity.hh:26
virtual const matrix4d & currentTransformation() const =0
Get the current transformation of the joint.
virtual unsigned int numberDof() const =0
Get the number of degrees of freedom of the joint.
virtual const vectorN & currentConfiguration() const =0
Get the current configuration of the robot.
Abstract class describing a humanoid robot with dynamics.
Definition: humanoid-dynamic-robot.hh:43
void linearVelocity(const vector3d &inLinearVelocity)
Set the linear velocity vector.
Definition: rigid-velocity.hh:50
virtual double upperTorqueBound(unsigned int inDofRank) const =0
Get the upper veocity bound of a given degree of freedom of the joint.
virtual CjrlHumanoidDynamicRobot * createHumanoidDynamicRobot()=0
Construct and return a pointer to a humanoid dynamic robot.
virtual bool getSpecializedInverseKinematics(const CjrlJoint &, const CjrlJoint &, const matrix4d &, const matrix4d &, vectorN &)
Compute Speciliazed InverseKinematics between two joints.
Definition: dynamic-robot.hh:398
jrlMathTools::Matrix3x3< double > matrix3d
virtual bool getOrientationJacobian(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
virtual void computeInertiaMatrix()=0
Compute the inertia matrix of the robot according wrt .
const vector3d & linearAcceleration() const
Get the linear acceleration vector.
Definition: rigid-acceleration.hh:41
virtual CjrlJoint * rightWrist() const =0
Get a pointer to the right wrist.
virtual const matrixNxP & currentForces() const =0
Get the current forces of the robot.
void rotationAcceleration(const vector3d &inRotationAcceleration)
Set the rotation acceleration vector.
Definition: rigid-acceleration.hh:59
virtual const vector3d & gazeDirection() const =0
Get the direction of gaze.
CjrlRigidVelocity(const vector3d &inLinearVelocity, const vector3d &inRotationVelocity)
Constructor.
Definition: rigid-velocity.hh:36
virtual CjrlJoint * createJointFreeflyer(const matrix4d &inInitialPosition)=0
Construct and return a pointer to a freeflyer joint.
virtual const std::vector< CjrlJoint * > & getActuatedJoints() const =0
Returns the list of actuated joints.
virtual double mass() const =0
Get the total mass of the robot.
virtual double upperBound(unsigned int inDofRank) const =0
Get the upper bound of a given degree of freedom of the joint.
virtual ~CjrlBody()
Destructor.
Definition: body.hh:46
virtual CjrlHand * rightHand() const =0
Get a pointer to the right hand.
virtual const matrix4d & initialPosition() const =0
Get the initial position of the joint.
virtual CjrlJoint * gazeJoint() const =0
Get gaze joint.
virtual CjrlJoint * associatedAnkle() const =0
Get the ankle to which the foot is attached.
const vector3d & linearVelocity() const
Get the linear velocity vector.
Definition: rigid-velocity.hh:44
virtual void getThumbAxis(vector3d &outThumbAxis) const =0
Get thumb axis when had is in open position.
virtual bool setHandClench(CjrlHand *inHand, double inClenchingValue)=0
Set the hand clench value.
virtual CjrlFoot * leftFoot() const =0
Get a pointer to the left foot.
virtual ~CjrlRobotDynamicsObjectFactory()
Destructor.
Definition: robot-dynamics-object-constructor.hh:27
virtual void setLinkedBody(CjrlBody &inBody)=0
Link a body to the joint.
virtual void setName(const std::string &name)=0
Set joint name.
void rotationVelocity(const vector3d &inRotationVelocity)
Set the rotation velocity vector.
Definition: rigid-velocity.hh:62
virtual void getSoleSize(double &outLength, double &outWidth) const =0
Get size of the rectagular sole.
virtual ~CjrlHumanoidDynamicRobot()
Destructor.
Definition: humanoid-dynamic-robot.hh:47
virtual const vector3d & localCenterOfMass() const =0
Get position of center of mass in joint local reference frame.
virtual void setJointOrderInConfig(std::vector< CjrlJoint * > inJointVector)=0
Set the joint ordering in the configuration vector.
virtual unsigned int numberDof() const =0
Get the number of degrees of freedom of the robot.
virtual double upperVelocityBoundDof(unsigned int inRankInConfiguration)=0
Get the upper velocity bound for ith dof.
virtual CjrlRigidVelocity jointVelocity() const =0
Get the velocity of the joint.
virtual void setAssociatedAnkle(CjrlJoint *inJoint)=0
Set the ankle to which the hand is attached.
virtual unsigned int countChildJoints() const =0
Get the number of children.
virtual double upperBoundDof(unsigned int inRankInConfiguration)=0
Get the upper bound for ith dof.
virtual void setCenter(const vector3d &inCenter)=0
Set the center of the hand.
virtual void setPalmNormal(const vector3d &inPalmNormal)=0
Set palm normal.
virtual bool getPositionJacobian(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
virtual void setForeFingerAxis(const vector3d &inForeFingerAxis)=0
Set forefinger axis.
virtual CjrlHand * createHand(CjrlJoint *inWristJoint)=0
Construct and return a pointer to a hand.
virtual bool isSupported(const std::string &)
Whether the specified property in implemented.
Definition: dynamic-robot.hh:392
boost_ublas::vector< double > vectorN
virtual const CjrlJoint * joint() const =0
Get const pointer to the joint the body is attached to.
This class represents a robot foot.
Definition: foot.hh:39
virtual const vector3d & gazeOrigin() const =0
Get a point on the gaze straight line.
virtual bool initialize()=0
Initialize data-structure necessary to dynamic computations This function should be called after buil...
struct jrlMathTools::Matrix4x4< double > matrix4d
virtual ~CjrlHand()
Destructor.
Definition: hand.hh:33
virtual double lowerBoundDof(unsigned int inRankInConfiguration)=0
Get the lower bound for ith dof.
virtual double lowerBound(unsigned int inDofRank) const =0
Get the lower bound of a given degree of freedom of the joint.
virtual CjrlJoint * childJoint(unsigned int inJointRank) const =0
Returns the child joint at the given rank.
virtual CjrlJoint * rightAnkle() const =0
Get a pointer to the right ankle.
virtual void setAssociatedWrist(CjrlJoint *inJoint)=0
Get the wrist joint to which the hand is attached.
virtual std::vector< CjrlJoint * > jointsFromRootToThis() const =0
Get a vector containing references of the joints between the rootJoint and this joint.
virtual bool computeForwardKinematics()=0
Compute forward kinematics.
virtual double mass() const =0
Get mass.
virtual void getJacobianPointWrtConfig(const vector3d &inPointJointFrame, matrixNxP &outjacobian) const =0
Get the jacobian of the point specified in local frame by inPointJointFrame.
virtual const vector3d & zeroMomentumPoint() const =0
return the coordinates of the Zero Momentum Point.
virtual const vectorN & currentAcceleration() const =0
Get the current acceleration of the robot.
virtual bool getProperty(const std::string &, std::string &) const
Get property corresponding to command name.
Definition: dynamic-robot.hh:380
virtual CjrlJoint * createJointRotation(const matrix4d &inInitialPosition)=0
Construct and return a pointer to a rotation joint.
virtual const vector3d & angularMomentumRobot()=0
Get the angular momentum of the robot at the center of mass.
boost_ublas::matrix< double > matrixNxP
CjrlRigidAcceleration(const vector3d &inLinearAcceleration, const vector3d &inRotationAcceleration)
Constructor.
Definition: rigid-acceleration.hh:34
virtual const vector3d & derivativeLinearMomentum()=0
Get the time-derivative of the linear momentum.
virtual double getHandClench(CjrlHand *inHand)=0
Get the hand clench value.
virtual bool computeCenterOfMassDynamics()=0
Compute the dynamics of the center of mass.
virtual double lowerTorqueBound(unsigned int inDofRank) const =0
Get the lower torque bound of a given degree of freedom of the joint.
virtual double lowerTorqueBoundDof(unsigned int inRankInConfiguration)=0
Get the lower torque bound for ith dof.
virtual void setActuatedJoints(std::vector< CjrlJoint * > &lActuatedJoints)=0
Specifies the list of actuated joints.
virtual ~CjrlFoot()
Destructor.
Definition: foot.hh:43
virtual double lowerVelocityBoundDof(unsigned int inRankInConfiguration)=0
Get the lower velocity bound for ith dof.
virtual CjrlJoint * leftWrist() const =0
Get a pointer to the left wrist.
The creation of an object.
Definition: robot-dynamics-object-constructor.hh:23
CjrlRigidVelocity()
Constructor.
Definition: rigid-velocity.hh:30
virtual void gaze(const vector3d &inDirection, const vector3d &inOrigin)=0
Set the gaze orientation and position in the local frame of the gaze joint.
virtual void computeJacobianJointWrtConfig()=0
Compute the joint's jacobian wrt the robot configuration.
virtual CjrlBody * createBody()=0
Construct and return a pointer to a body.
virtual const vector3d & accelerationCenterOfMass()=0
Get the acceleration of the center of mass.
virtual ~CjrlJoint()
Destructor.
Definition: joint.hh:79
This class represents the acceleration of a rigid body.
Definition: rigid-acceleration.hh:30
virtual CjrlRigidAcceleration jointAcceleration() const =0
Get the acceleration of the joint.
virtual const std::string & getName() const =0
Get joint name.
virtual const matrixNxP & inertiaMatrix() const =0
Get the inertia matrix of the robot according wrt .
virtual std::vector< CjrlJoint * > jointsBetween(const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const =0
Get the chain of joints between two joints.
This class represents a robot hand.
Definition: hand.hh:29
const vector3d & rotationAcceleration() const
Get the rotation acceleration vector.
Definition: rigid-acceleration.hh:53
virtual const vector3d & positionCenterOfMass() const =0
Get the position of the center of mass.
virtual bool addChildJoint(CjrlJoint &inJoint)=0
Add a child joint.
virtual CjrlDynamicRobot * createDynamicRobot()=0
Construct and return a pointer to a dynamic robot.
virtual void setThumbAxis(const vector3d &inThumbAxis)=0
Set thumb axis in wrist frame when had is in open position.
virtual CjrlJoint * parentJoint() const =0
Get a pointer to the parent joint (if any).
virtual void setAnklePositionInLocalFrame(const vector3d &inCoordinates)=0
Set position of the ankle in the foot local coordinate frame.
virtual double upperTorqueBoundDof(unsigned int inRankInConfiguration)=0
Get the upper torque bound for ith dof.
virtual std::vector< CjrlJoint * > jointVector()=0
Get a vector containing all the joints.
virtual const vector3d & derivativeAngularMomentum()=0
Get the time-derivative of the angular momentum at the center of mass.
virtual const vectorN & currentVelocity() const =0
Get the current velocity of the robot.
virtual void setSoleSize(const double &inLength, const double &inWidth)=0
Set size of the rectagular sole.
virtual CjrlBody * linkedBody() const =0
Get a pointer to the linked body (if any).
virtual CjrlJoint * chest() const =0
Get a pointer to the chest.
virtual CjrlJoint * waist() const =0
Get a pointer to the waist.
virtual unsigned int rankInConfiguration() const =0
Get the rank of this joint in the robot configuration vector.
virtual const vector3d & velocityCenterOfMass()=0
Get the velocity of the center of mass.
virtual const matrix3d & inertiaMatrix() const =0
Get Intertia matrix expressed in joint local reference frame.
virtual const matrixNxP & currentTorques() const =0
Get the current torques of the robot.
void linearAcceleration(const vector3d &inLinearAcceleration)
Set the linear acceleration vector.
Definition: rigid-acceleration.hh:47
virtual void getForeFingerAxis(vector3d &outForeFingerAxis) const =0
Get forefinger axis.