hpp::model::Joint Class Referenceabstract

Robot joint. More...

#include <hpp/model/joint.hh>

Inheritance diagram for hpp::model::Joint:
Collaboration diagram for hpp::model::Joint:

Public Member Functions

const size_typenumberDof () const
 Return number of degrees of freedom. More...
 
const size_typeconfigSize () const
 Return number of degrees of freedom. More...
 
const size_typerankInConfiguration () const
 Return rank of the joint in the configuration vector. More...
 
size_type rankInVelocity () const
 Return rank of the joint in the velocity vector. More...
 
JointConfigurationconfiguration () const
 Access to configuration space. More...
 
void robot (const DeviceWkPtr_t &device)
 Set robot owning the kinematic chain. More...
 
DeviceConstPtr_t robot () const
 Access robot owning the object. More...
 
DevicePtr_t robot ()
 Access robot owning the object. More...
 
virtual std::ostream & display (std::ostream &os) const
 Display joint. More...
 
Construction and copy and destruction
 Joint (const Transform3f &initialPosition, size_type configSize, size_type numberDof)
 Constructor. More...
 
 Joint (const Joint &joint)
 Copy constructor. More...
 
virtual JointPtr_t clone () const =0
 Return pointer to copy of this. More...
 
virtual ~Joint ()
 
Name
virtual void name (const std::string &name)
 Set name. More...
 
virtual const std::string & name () const
 Get name. More...
 
Position
const Transform3finitialPosition () const
 Joint initial position (when robot is in zero configuration) More...
 
const Transform3fcurrentTransformation () const
 Joint transformation. More...
 
virtual void computePosition (ConfigurationIn_t configuration, const Transform3f &parentPosition, Transform3f &position) const =0
 Compute position of joint. More...
 
vector_t neutralConfiguration () const
 Get neutral configuration of joint. More...
 
Kinematic chain
JointPtr_t parentJoint () const
 Get a pointer to the parent joint (if any). More...
 
void addChildJoint (JointPtr_t joint, bool computePositionInParent=true)
 Add child joint. More...
 
std::size_t numberChildJoints () const
 Number of child joints. More...
 
JointPtr_t childJoint (std::size_t rank) const
 Get child joint. More...
 
const Transform3fpositionInParentFrame () const
 Get position of joint in parent frame. More...
 
void positionInParentFrame (const Transform3f &p)
 Set position of joint in parent frame. More...
 
Bounds

Set whether given degree of freedom is bounded

void isBounded (size_type rank, bool bounded)
 
bool isBounded (size_type rank) const
 Get whether given degree of freedom is bounded. More...
 
value_type lowerBound (size_type rank) const
 Get lower bound of given degree of freedom. More...
 
value_type upperBound (size_type rank) const
 Get upper bound of given degree of freedom. More...
 
void lowerBound (size_type rank, value_type lowerBound)
 Set lower bound of given degree of freedom. More...
 
void upperBound (size_type rank, value_type upperBound)
 Set upper bound of given degree of freedom. More...
 
virtual value_type upperBoundLinearVelocity () const =0
 Get upper bound on linear velocity of the joint frame. More...
 
virtual value_type upperBoundAngularVelocity () const =0
 Get upper bound on angular velocity of the joint frame. More...
 
const value_typemaximalDistanceToParent () const
 Maximal distance of joint origin to parent origin. More...
 
Jacobian
const JointJacobian_tjacobian () const
 Get const reference to Jacobian. More...
 
JointJacobian_tjacobian ()
 Get non const reference to Jacobian. More...
 
Body linked to the joint

Get linked body

BodyPtr_t linkedBody () const
 
void setLinkedBody (const BodyPtr_t &body)
 Set linked body. More...
 
Compatibility with urdf
const Transform3flinkInJointFrame () const
 Get urdf link position in joint frame. More...
 
void linkInJointFrame (const Transform3f &transform)
 Set urdf link position in joint frame. More...
 
const std::string & linkName () const
 Get link name. More...
 
void linkName (const std::string &linkName)
 Set link name. More...
 

Protected Member Functions

virtual void computeMaximalDistanceToParent ()=0
 

Protected Attributes

JointConfigurationconfiguration_
 
Transform3f currentTransformation_
 
Transform3f positionInParentFrame_
 
Transform3f linkInJointFrame_
 
Transform3f T3f_
 
value_type mass_
 Mass of this and all descendants. More...
 
fcl::Vec3f massCom_
 Mass time center of mass of this and all descendants. More...
 
value_type maximalDistanceToParent_
 
vector_t neutralConfiguration_
 

Friends

class Device
 
class ChildrenIterator
 
class CenterOfMassComputation
 

Detailed Description

Robot joint.

A joint maps an input vector to a transformation of SE(3) from the parent frame to the joint frame.

The input vector is provided through the configuration vector of the robot the joint belongs to. The joint input vector is composed of the components of the robot configuration starting at Joint::rankInConfiguration.

The joint input vector represents a element of a Lie group, either

Operations specific to joints (uniform sampling of input space, straight interpolation, distance, ...) are performed by a JointConfiguration instance that has the same class hierarchy as Joint.

Constructor & Destructor Documentation

◆ Joint() [1/2]

hpp::model::Joint::Joint ( const Transform3f initialPosition,
size_type  configSize,
size_type  numberDof 
)

Constructor.

Parameters
initialPositionposition of the joint before being inserted in a kinematic chain,
configSizedimension of the configuration vector,
numberDofdimension of the velocity vector.

◆ Joint() [2/2]

hpp::model::Joint::Joint ( const Joint joint)

Copy constructor.

Clone body and therefore inner and outer objects (see Body::clone).

◆ ~Joint()

virtual hpp::model::Joint::~Joint ( )
virtual

Member Function Documentation

◆ addChildJoint()

void hpp::model::Joint::addChildJoint ( JointPtr_t  joint,
bool  computePositionInParent = true 
)

Add child joint.

Parameters
jointchild joint added to this one,
computePositionInParentwhether to compute position of the child joint in this one's frame.
Note
When building a kinematic chain, we usually build the joint in its initial position and compute the (constant) position of the joint in its parent when adding the joint in the kinematic chain. When copying a kinematic chain, we copy the position of the joint in its parent frame and therefore we do not update it when adding the joint in the kinematic chain.

◆ childJoint()

JointPtr_t hpp::model::Joint::childJoint ( std::size_t  rank) const
inline

Get child joint.

Referenced by hpp::model::ChildrenIterator::operator++().

◆ clone()

virtual JointPtr_t hpp::model::Joint::clone ( ) const
pure virtual

◆ computeMaximalDistanceToParent()

virtual void hpp::model::Joint::computeMaximalDistanceToParent ( )
protectedpure virtual

◆ computePosition()

virtual void hpp::model::Joint::computePosition ( ConfigurationIn_t  configuration,
const Transform3f parentPosition,
Transform3f position 
) const
pure virtual

Compute position of joint.

Parameters
configurationthe configuration of the robot,
parentPositionposition of parent joint,
Return values
positionposition of this joint.

Implemented in hpp::model::JointTranslation< dimension >, hpp::model::jointRotation::Bounded, hpp::model::jointRotation::UnBounded, hpp::model::JointRotation, hpp::model::JointSO3, and hpp::model::JointAnchor.

◆ configSize()

const size_type& hpp::model::Joint::configSize ( ) const
inline

Return number of degrees of freedom.

◆ configuration()

JointConfiguration* hpp::model::Joint::configuration ( ) const
inline

Access to configuration space.

◆ currentTransformation()

const Transform3f& hpp::model::Joint::currentTransformation ( ) const

Joint transformation.

◆ display()

virtual std::ostream& hpp::model::Joint::display ( std::ostream &  os) const
virtual

Display joint.

◆ initialPosition()

const Transform3f& hpp::model::Joint::initialPosition ( ) const

Joint initial position (when robot is in zero configuration)

◆ isBounded() [1/2]

void hpp::model::Joint::isBounded ( size_type  rank,
bool  bounded 
)

◆ isBounded() [2/2]

bool hpp::model::Joint::isBounded ( size_type  rank) const

Get whether given degree of freedom is bounded.

◆ jacobian() [1/2]

const JointJacobian_t& hpp::model::Joint::jacobian ( ) const
inline

Get const reference to Jacobian.

◆ jacobian() [2/2]

JointJacobian_t& hpp::model::Joint::jacobian ( )
inline

Get non const reference to Jacobian.

◆ linkedBody()

BodyPtr_t hpp::model::Joint::linkedBody ( ) const

◆ linkInJointFrame() [1/2]

const Transform3f& hpp::model::Joint::linkInJointFrame ( ) const
inline

Get urdf link position in joint frame.

When parsing urdf models, joint frames are reoriented in order to rotate about their x-axis. For some applications, it is necessary to be able to recover the position of the urdf link attached to the joint.

◆ linkInJointFrame() [2/2]

void hpp::model::Joint::linkInJointFrame ( const Transform3f transform)
inline

Set urdf link position in joint frame.

◆ linkName() [1/2]

const std::string& hpp::model::Joint::linkName ( ) const
inline

Get link name.

◆ linkName() [2/2]

void hpp::model::Joint::linkName ( const std::string &  linkName)
inline

Set link name.

◆ lowerBound() [1/2]

value_type hpp::model::Joint::lowerBound ( size_type  rank) const

Get lower bound of given degree of freedom.

◆ lowerBound() [2/2]

void hpp::model::Joint::lowerBound ( size_type  rank,
value_type  lowerBound 
)

Set lower bound of given degree of freedom.

◆ maximalDistanceToParent()

const value_type& hpp::model::Joint::maximalDistanceToParent ( ) const
inline

Maximal distance of joint origin to parent origin.

◆ name() [1/2]

virtual void hpp::model::Joint::name ( const std::string &  name)
inlinevirtual

Set name.

◆ name() [2/2]

virtual const std::string& hpp::model::Joint::name ( ) const
inlinevirtual

Get name.

◆ neutralConfiguration()

vector_t hpp::model::Joint::neutralConfiguration ( ) const
inline

Get neutral configuration of joint.

Neutral configuration is

  • 0 for translation joints,
  • (1,0,0,0) for SO3 joints,
  • (1,0) for unbounded rotation joint
  • 0 for bounded rotation joint.

◆ numberChildJoints()

std::size_t hpp::model::Joint::numberChildJoints ( ) const
inline

Number of child joints.

Referenced by hpp::model::ChildrenIterator::operator++().

◆ numberDof()

const size_type& hpp::model::Joint::numberDof ( ) const
inline

Return number of degrees of freedom.

◆ parentJoint()

JointPtr_t hpp::model::Joint::parentJoint ( ) const
inline

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

◆ positionInParentFrame() [1/2]

const Transform3f& hpp::model::Joint::positionInParentFrame ( ) const
inline

Get position of joint in parent frame.

◆ positionInParentFrame() [2/2]

void hpp::model::Joint::positionInParentFrame ( const Transform3f p)
inline

Set position of joint in parent frame.

◆ rankInConfiguration()

const size_type& hpp::model::Joint::rankInConfiguration ( ) const
inline

Return rank of the joint in the configuration vector.

◆ rankInVelocity()

size_type hpp::model::Joint::rankInVelocity ( ) const
inline

Return rank of the joint in the velocity vector.

◆ robot() [1/3]

void hpp::model::Joint::robot ( const DeviceWkPtr_t &  device)
inline

Set robot owning the kinematic chain.

◆ robot() [2/3]

DeviceConstPtr_t hpp::model::Joint::robot ( ) const
inline

Access robot owning the object.

◆ robot() [3/3]

DevicePtr_t hpp::model::Joint::robot ( )
inline

Access robot owning the object.

◆ setLinkedBody()

void hpp::model::Joint::setLinkedBody ( const BodyPtr_t body)

Set linked body.

◆ upperBound() [1/2]

value_type hpp::model::Joint::upperBound ( size_type  rank) const

Get upper bound of given degree of freedom.

◆ upperBound() [2/2]

void hpp::model::Joint::upperBound ( size_type  rank,
value_type  upperBound 
)

Set upper bound of given degree of freedom.

◆ upperBoundAngularVelocity()

virtual value_type hpp::model::Joint::upperBoundAngularVelocity ( ) const
pure virtual

Get upper bound on angular velocity of the joint frame.

Returns
coefficient $\lambda$ such that

\begin{equation*} \forall \mathbf{q}_{joint}\ \ \ \ \ \ \|\omega\| \leq \lambda \|\mathbf{\dot{q}}_{joint}\| \end{equation*}

where
  • $\mathbf{q}_{joint}$ is any joint configuration,
  • $\mathbf{\dot{q}}_{joint}$ is the joint velocity, and
  • $\omega$ is the angular velocity of the joint frame.

Implemented in hpp::model::JointTranslation< dimension >, hpp::model::JointRotation, hpp::model::JointSO3, and hpp::model::JointAnchor.

◆ upperBoundLinearVelocity()

virtual value_type hpp::model::Joint::upperBoundLinearVelocity ( ) const
pure virtual

Get upper bound on linear velocity of the joint frame.

Returns
coefficient $\lambda$ such that

\begin{equation*} \forall \mathbf{q}_{joint}\ \ \ \ \ \ \|\mathbf {v}\| \leq \lambda \|\mathbf{\dot{q}}_{joint}\| \end{equation*}

where
  • $\mathbf{q}_{joint}$ is any joint configuration,
  • $\mathbf{\dot{q}}_{joint}$ is the joint velocity, and
  • $\mathbf{v}$ is the linear velocity of the joint frame.

Implemented in hpp::model::JointTranslation< dimension >, hpp::model::JointRotation, hpp::model::JointSO3, and hpp::model::JointAnchor.

Friends And Related Function Documentation

◆ CenterOfMassComputation

friend class CenterOfMassComputation
friend

◆ ChildrenIterator

friend class ChildrenIterator
friend

◆ Device

friend class Device
friend

Member Data Documentation

◆ configuration_

JointConfiguration* hpp::model::Joint::configuration_
protected

◆ currentTransformation_

Transform3f hpp::model::Joint::currentTransformation_
mutableprotected

◆ linkInJointFrame_

Transform3f hpp::model::Joint::linkInJointFrame_
protected

◆ mass_

value_type hpp::model::Joint::mass_
protected

Mass of this and all descendants.

◆ massCom_

fcl::Vec3f hpp::model::Joint::massCom_
protected

Mass time center of mass of this and all descendants.

◆ maximalDistanceToParent_

value_type hpp::model::Joint::maximalDistanceToParent_
protected

◆ neutralConfiguration_

vector_t hpp::model::Joint::neutralConfiguration_
protected

◆ positionInParentFrame_

Transform3f hpp::model::Joint::positionInParentFrame_
protected

◆ T3f_

Transform3f hpp::model::Joint::T3f_
mutableprotected