|
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. More...
|
|
virtual bool | getPositionJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0 |
|
virtual bool | getOrientationJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0 |
|
virtual bool | getJacobianCenterOfMass (const CjrlJoint &inStartJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0 |
|
virtual bool | getSpecializedInverseKinematics (const CjrlJoint &, const CjrlJoint &, const matrix4d &, const matrix4d &, vectorN &) |
| Compute Speciliazed InverseKinematics between two joints. More...
|
|
|
virtual bool | initialize ()=0 |
| Initialize data-structure necessary to dynamic computations This function should be called after building the tree of joints. More...
|
|
virtual | ~CjrlDynamicRobot () |
| Destructor. More...
|
|
|
virtual void | rootJoint (CjrlJoint &inJoint)=0 |
| Set the root joint of the robot. More...
|
|
virtual CjrlJoint * | rootJoint () const =0 |
| Get the root joint of the robot. More...
|
|
virtual std::vector< CjrlJoint * > | jointVector ()=0 |
| Get a vector containing all the joints. More...
|
|
virtual std::vector< CjrlJoint * > | jointsBetween (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const =0 |
| Get the chain of joints between two joints. More...
|
|
virtual double | upperBoundDof (unsigned int inRankInConfiguration)=0 |
| Get the upper bound for ith dof. More...
|
|
virtual double | lowerBoundDof (unsigned int inRankInConfiguration)=0 |
| Get the lower bound for ith dof. More...
|
|
virtual double | upperBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)=0 |
| Compute the upper bound for ith dof using other configuration values if possible. More...
|
|
virtual double | lowerBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)=0 |
| Compute the lower bound for ith dof using other configuration values if possible. More...
|
|
virtual double | upperVelocityBoundDof (unsigned int inRankInConfiguration)=0 |
| Get the upper velocity bound for ith dof. More...
|
|
virtual double | lowerVelocityBoundDof (unsigned int inRankInConfiguration)=0 |
| Get the lower velocity bound for ith dof. More...
|
|
virtual double | upperTorqueBoundDof (unsigned int inRankInConfiguration)=0 |
| Get the upper torque bound for ith dof. More...
|
|
virtual double | lowerTorqueBoundDof (unsigned int inRankInConfiguration)=0 |
| Get the lower torque bound for ith dof. More...
|
|
virtual unsigned int | numberDof () const =0 |
| Get the number of degrees of freedom of the robot. More...
|
|
virtual void | setJointOrderInConfig (std::vector< CjrlJoint *> inJointVector)=0 |
| Set the joint ordering in the configuration vector. More...
|
|
|
virtual bool | currentConfiguration (const vectorN &inConfig)=0 |
| Set the current configuration of the robot. More...
|
|
virtual const vectorN & | currentConfiguration () const =0 |
| Get the current configuration of the robot. More...
|
|
virtual bool | currentVelocity (const vectorN &inVelocity)=0 |
| Set the current velocity of the robot. More...
|
|
virtual const vectorN & | currentVelocity () const =0 |
| Get the current velocity of the robot. More...
|
|
virtual bool | currentAcceleration (const vectorN &inAcceleration)=0 |
| Set the current acceleration of the robot. More...
|
|
virtual const vectorN & | currentAcceleration () const =0 |
| Get the current acceleration of the robot. More...
|
|
virtual const matrixNxP & | currentForces () const =0 |
| Get the current forces of the robot. More...
|
|
virtual const matrixNxP & | currentTorques () const =0 |
| Get the current torques of the robot. More...
|
|
virtual const vectorN & | currentJointTorques () const =0 |
| Get the current joint torques of the robot. More...
|
|
|
virtual bool | computeForwardKinematics ()=0 |
| Compute forward kinematics. More...
|
|
virtual bool | computeCenterOfMassDynamics ()=0 |
| Compute the dynamics of the center of mass. More...
|
|
virtual const vector3d & | positionCenterOfMass () const =0 |
| Get the position of the center of mass. More...
|
|
virtual const vector3d & | velocityCenterOfMass ()=0 |
| Get the velocity of the center of mass. More...
|
|
virtual const vector3d & | accelerationCenterOfMass ()=0 |
| Get the acceleration of the center of mass. More...
|
|
virtual const vector3d & | linearMomentumRobot ()=0 |
| Get the linear momentum of the robot. More...
|
|
virtual const vector3d & | derivativeLinearMomentum ()=0 |
| Get the time-derivative of the linear momentum. More...
|
|
virtual const vector3d & | angularMomentumRobot ()=0 |
| Get the angular momentum of the robot at the center of mass. More...
|
|
virtual const vector3d & | derivativeAngularMomentum ()=0 |
| Get the time-derivative of the angular momentum at the center of mass. More...
|
|
virtual double | mass () const =0 |
| Get the total mass of the robot. More...
|
|
|
virtual bool | isSupported (const std::string &) |
| Whether the specified property in implemented. More...
|
|
virtual bool | getProperty (const std::string &, std::string &) const |
| Get property corresponding to command name. More...
|
|
virtual bool | setProperty (std::string &, const std::string &) |
| Set property corresponding to command name. More...
|
|
|
virtual void | computeInertiaMatrix ()=0 |
| Compute the inertia matrix of the robot according wrt . More...
|
|
virtual const matrixNxP & | inertiaMatrix () const =0 |
| Get the inertia matrix of the robot according wrt . More...
|
|
|
virtual const std::vector< CjrlJoint * > & | getActuatedJoints () const =0 |
| Returns the list of actuated joints. More...
|
|
virtual void | setActuatedJoints (std::vector< CjrlJoint *> &lActuatedJoints)=0 |
| Specifies the list of actuated joints. More...
|
|
Abstract class that instantiates a robot with dynamic properties.
- Definition
- A robot is a kinematic chain of joints. To each joint is attached a body. Each body has a mass and inertia matrix. The kinematic chain is recursively constructed by adding children to each joint. (See CjrlJoint). The configuration of a robot is defined by a vector
called the configuration vector and containing the values of each degree of freedom. The dimension of this vector is denoted by
.
The time derivative
of the configuration vector is called the velocity vector.
The time derivative
of the velocity vector. is called the acceleration vector.
- Control of the implementation
- In some cases, it is desirable to control the implementation of this class in order to selectively compute only some kinematic and dynamic values. For instance, for speed of computation purposes, one may want to compute only velocities and not accelerations. In order to keep the interface light, a control mechanism based on properties is proposed through the following methods: isSupported(), getProperty(), setProperty(). Each implementation is responsible for its own methods. However, in order to keep some compatibility, some recommended methods are listed in this page.
- Actuated Joints.
- In order to make a distinction between actuated joints and none actuacted joints, a vector of actuated joints is provided through method: getActuatedJoints().