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