CjrlJoint Class Referenceabstract

This class represents a robot joint. More...

#include <abstract-robot-dynamics/joint.hh>

Public Member Functions

virtual ~CjrlJoint ()
 Destructor. More...
 
Joint name
virtual const std::string & getName () const =0
 Get joint name. More...
 
virtual void setName (const std::string &name)=0
 Set joint name. More...
 
Joint hierarchy.
virtual CjrlJointparentJoint () const =0
 Get a pointer to the parent joint (if any). More...
 
virtual bool addChildJoint (CjrlJoint &inJoint)=0
 Add a child joint. More...
 
virtual unsigned int countChildJoints () const =0
 Get the number of children. More...
 
virtual CjrlJointchildJoint (unsigned int inJointRank) const =0
 Returns the child joint at the given rank. More...
 
virtual std::vector< CjrlJoint * > jointsFromRootToThis () const =0
 Get a vector containing references of the joints between the rootJoint and this joint. More...
 
virtual unsigned int rankInConfiguration () const =0
 Get the rank of this joint in the robot configuration vector. More...
 
Joint kinematics
virtual const matrix4dinitialPosition () const =0
 Get the initial position of the joint. More...
 
virtual const matrix4dcurrentTransformation () const =0
 Get the current transformation of the joint. More...
 
virtual CjrlRigidVelocity jointVelocity () const =0
 Get the velocity $({\bf v}, {\bf \omega})$ of the joint. More...
 
virtual CjrlRigidAcceleration jointAcceleration () const =0
 Get the acceleration of the joint. More...
 
virtual unsigned int numberDof () const =0
 Get the number of degrees of freedom of the joint. More...
 
Bounds of the degrees of freedom
virtual double lowerBound (unsigned int inDofRank) const =0
 Get the lower bound of a given degree of freedom of the joint. More...
 
virtual double upperBound (unsigned int inDofRank) const =0
 Get the upper bound of a given degree of freedom of the joint. More...
 
virtual void lowerBound (unsigned int inDofRank, double inLowerBound)=0
 Set the lower bound of a given degree of freedom of the joint. More...
 
virtual void upperBound (unsigned int inDofRank, double inUpperBound)=0
 Set the upper bound of a given degree of freedom of the joint. More...
 
virtual double lowerVelocityBound (unsigned int inDofRank) const =0
 Get the lower velocity bound of a given degree of freedom of the joint. More...
 
virtual double upperVelocityBound (unsigned int inDofRank) const =0
 Get the upper veocity bound of a given degree of freedom of the joint. More...
 
virtual void lowerVelocityBound (unsigned int inDofRank, double inLowerBound)=0
 Set the lower velocity bound of a given degree of freedom of the joint. More...
 
virtual void upperVelocityBound (unsigned int inDofRank, double inUpperBound)=0
 Set the upper velocity bound of a given degree of freedom of the joint. More...
 
virtual double lowerTorqueBound (unsigned int inDofRank) const =0
 Get the lower torque bound of a given degree of freedom of the joint. More...
 
virtual double upperTorqueBound (unsigned int inDofRank) const =0
 Get the upper veocity bound of a given degree of freedom of the joint. More...
 
virtual void lowerTorqueBound (unsigned int inDofRank, double inLowerBound)=0
 Set the lower torque bound of a given degree of freedom of the joint. More...
 
virtual void upperTorqueBound (unsigned int inDofRank, double inUpperBound)=0
 Set the upper torque bound of a given degree of freedom of the joint. More...
 
Jacobian functions wrt configuration.
virtual const matrixNxPjacobianJointWrtConfig () const =0
 Get the Jacobian matrix of the joint position and orientation wrt the robot configuration. More...
 
virtual void computeJacobianJointWrtConfig ()=0
 Compute the joint's jacobian wrt the robot configuration. More...
 
virtual void getJacobianPointWrtConfig (const vector3d &inPointJointFrame, matrixNxP &outjacobian) const =0
 Get the jacobian of the point specified in local frame by inPointJointFrame. More...
 
Body linked to the joint
virtual CjrlBodylinkedBody () const =0
 Get a pointer to the linked body (if any). More...
 
virtual void setLinkedBody (CjrlBody &inBody)=0
 Link a body to the joint. More...
 

Detailed Description

This class represents a robot joint.

A joint may have several degrees of freedom. The position, velocity and acceleration of a joint are defined by the configuration vector ${\bf q}$ and its first and second derivatives.

Several rigid-body transformations represented by matrix4d type are considered in the following functions.

Three types of joints are considered and defined as follows.

  • Freeflyer joint has 6 degrees of freedom. In identity initial position, the degrees of freedom respectively correspond to translation along x,y,z and roll, pitch, yaw angles.
  • Rotation joint has 1 degree of freedom. In identity initial position, the joint rotates about x-axis.
  • Translation joint has 1 degree of freedom. In identity initial position, the joint translates about x-axis.
joint.png
Definition of initial and current

transformation of a joint."

transformation of a joint."

As an example, let us denote by

  • $M_{init} \in SE(3)$, the initial position of a joint, that is the position when all the degrees of freedom of the robot are set to 0.
  • $M_{cur}({\bf q}) \in SE(3)$, the current position of the joint, when robot is in configuration ${\bf q}$.
  • ${\bf p} \in {\bf R}^3$ a point attached to the joint when the robot is in initial configuration (all degrees of freedom are set to 0).

The position of the point in configuration ${\bf q}$ is given by

\[ M_{cur}({\bf q}).M_{init}^{-1}.{\bf p} \]

Constructor & Destructor Documentation

◆ ~CjrlJoint()

virtual CjrlJoint::~CjrlJoint ( )
inlinevirtual

Destructor.

Member Function Documentation

◆ addChildJoint()

virtual bool CjrlJoint::addChildJoint ( CjrlJoint inJoint)
pure virtual

Add a child joint.

◆ childJoint()

virtual CjrlJoint* CjrlJoint::childJoint ( unsigned int  inJointRank) const
pure virtual

Returns the child joint at the given rank.

◆ computeJacobianJointWrtConfig()

virtual void CjrlJoint::computeJacobianJointWrtConfig ( )
pure virtual

Compute the joint's jacobian wrt the robot configuration.

◆ countChildJoints()

virtual unsigned int CjrlJoint::countChildJoints ( ) const
pure virtual

Get the number of children.

◆ currentTransformation()

virtual const matrix4d& CjrlJoint::currentTransformation ( ) const
pure virtual

Get the current transformation of the joint.

The current transformation of the joint is the transformation moving the joint from the position in initial configuration to the current position.

The current transformation is determined by the configuration ${\bf q}$ of the robot.

◆ getJacobianPointWrtConfig()

virtual void CjrlJoint::getJacobianPointWrtConfig ( const vector3d inPointJointFrame,
matrixNxP outjacobian 
) const
pure virtual

Get the jacobian of the point specified in local frame by inPointJointFrame.

The output matrix outjacobian is automatically resized if necessary

◆ getName()

virtual const std::string& CjrlJoint::getName ( ) const
pure virtual

Get joint name.

◆ initialPosition()

virtual const matrix4d& CjrlJoint::initialPosition ( ) const
pure virtual

Get the initial position of the joint.

The initial position of the joint is the position of the local frame of the joint.

◆ jacobianJointWrtConfig()

virtual const matrixNxP& CjrlJoint::jacobianJointWrtConfig ( ) const
pure virtual

Get the Jacobian matrix of the joint position and orientation wrt the robot configuration.

Kinematical constraints from interaction with the environment are not taken into account for this computation.

The corresponding computation can be done by the robot for each of its joints or by the joint.

Returns
a matrix $J \in {\bf R}^{6\times n_{dof}}$ defined by

\[ J = \left(\begin{array}{llll} {\bf v_1} & {\bf v_2} & \cdots & {\bf v_{n_{dof}}} \\ {\bf \omega_1} & {\bf \omega_2} & \cdots & {\bf \omega_{n_{dof}}} \end{array}\right) \]

where ${\bf v_i}$ and ${\bf \omega_i}$ are respectively the linear and angular velocities of the joint implied by the variation of degree of freedom $q_i$. The velocity of the joint returned by CjrlJoint::jointVelocity can thus be obtained through the following formula:

\[ \left(\begin{array}{l} {\bf v} \\ {\bf \omega}\end{array}\right) = J {\bf \dot{q}} \]

◆ jointAcceleration()

virtual CjrlRigidAcceleration CjrlJoint::jointAcceleration ( ) const
pure virtual

Get the acceleration of the joint.

The acceleration is determined by the configuration of the robot and its first and second time derivative: $({\bf q},{\bf \dot{q}}, {\bf \ddot{q}})$.

◆ jointsFromRootToThis()

virtual std::vector<CjrlJoint*> CjrlJoint::jointsFromRootToThis ( ) const
pure virtual

Get a vector containing references of the joints between the rootJoint and this joint.

The root Joint and this Joint are included in the vector.

◆ jointVelocity()

virtual CjrlRigidVelocity CjrlJoint::jointVelocity ( ) const
pure virtual

Get the velocity $({\bf v}, {\bf \omega})$ of the joint.

The velocity is determined by the configuration of the robot and its time derivative: $({\bf q},{\bf \dot{q}})$.

Returns
the linear velocity ${\bf v}$ of the origin of the joint frame and the angular velocity ${\bf \omega}$ of the joint frame.

◆ linkedBody()

virtual CjrlBody* CjrlJoint::linkedBody ( ) const
pure virtual

Get a pointer to the linked body (if any).

◆ lowerBound() [1/2]

virtual double CjrlJoint::lowerBound ( unsigned int  inDofRank) const
pure virtual

Get the lower bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint

◆ lowerBound() [2/2]

virtual void CjrlJoint::lowerBound ( unsigned int  inDofRank,
double  inLowerBound 
)
pure virtual

Set the lower bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint
inLowerBoundlower bound

◆ lowerTorqueBound() [1/2]

virtual double CjrlJoint::lowerTorqueBound ( unsigned int  inDofRank) const
pure virtual

Get the lower torque bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint

◆ lowerTorqueBound() [2/2]

virtual void CjrlJoint::lowerTorqueBound ( unsigned int  inDofRank,
double  inLowerBound 
)
pure virtual

Set the lower torque bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint
inLowerBoundlower bound

◆ lowerVelocityBound() [1/2]

virtual double CjrlJoint::lowerVelocityBound ( unsigned int  inDofRank) const
pure virtual

Get the lower velocity bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint

◆ lowerVelocityBound() [2/2]

virtual void CjrlJoint::lowerVelocityBound ( unsigned int  inDofRank,
double  inLowerBound 
)
pure virtual

Set the lower velocity bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint
inLowerBoundlower bound

◆ numberDof()

virtual unsigned int CjrlJoint::numberDof ( ) const
pure virtual

Get the number of degrees of freedom of the joint.

◆ parentJoint()

virtual CjrlJoint* CjrlJoint::parentJoint ( ) const
pure virtual

Get a pointer to the parent joint (if any).

◆ rankInConfiguration()

virtual unsigned int CjrlJoint::rankInConfiguration ( ) const
pure virtual

Get the rank of this joint in the robot configuration vector.

If the Joint has several degrees of freedom, it is the rank of the first degree of freedom.

◆ setLinkedBody()

virtual void CjrlJoint::setLinkedBody ( CjrlBody inBody)
pure virtual

Link a body to the joint.

◆ setName()

virtual void CjrlJoint::setName ( const std::string &  name)
pure virtual

Set joint name.

◆ upperBound() [1/2]

virtual double CjrlJoint::upperBound ( unsigned int  inDofRank) const
pure virtual

Get the upper bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint

◆ upperBound() [2/2]

virtual void CjrlJoint::upperBound ( unsigned int  inDofRank,
double  inUpperBound 
)
pure virtual

Set the upper bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint
inUpperBoundUpper bound.

◆ upperTorqueBound() [1/2]

virtual double CjrlJoint::upperTorqueBound ( unsigned int  inDofRank) const
pure virtual

Get the upper veocity bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint

◆ upperTorqueBound() [2/2]

virtual void CjrlJoint::upperTorqueBound ( unsigned int  inDofRank,
double  inUpperBound 
)
pure virtual

Set the upper torque bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint
inUpperBoundUpper bound.

◆ upperVelocityBound() [1/2]

virtual double CjrlJoint::upperVelocityBound ( unsigned int  inDofRank) const
pure virtual

Get the upper veocity bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint

◆ upperVelocityBound() [2/2]

virtual void CjrlJoint::upperVelocityBound ( unsigned int  inDofRank,
double  inUpperBound 
)
pure virtual

Set the upper velocity bound of a given degree of freedom of the joint.

Parameters
inDofRankId of the dof in the joint
inUpperBoundUpper bound.