hpp::model::Joint Class Reference

Robot joint. More...

#include <hpp/model/joint.hh>

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

List of all members.

Public Member Functions

const Transform3finitialPosition () const
 Joint initial position (when robot is in zero configuration)
const Transform3fcurrentTransformation () const
 Joint transformation.
virtual void computePosition (ConfigurationIn_t configuration, const Transform3f &parentPosition, Transform3f &position) const =0
 Compute position of joint.
vector_t neutralConfiguration () const
 Get neutral configuration of joint.
const size_typenumberDof () const
 Return number of degrees of freedom.
const size_typeconfigSize () const
 Return number of degrees of freedom.
const size_typerankInConfiguration () const
 Return rank of the joint in the configuration vector.
size_type rankInVelocity () const
 Return rank of the joint in the velocity vector.
JointConfigurationconfiguration () const
void robot (const DeviceWkPtr_t &device)
 Set robot owning the kinematic chain.
DeviceConstPtr_t robot () const
 Access robot owning the object.
DevicePtr_t robot ()
 Access robot owning the object.
virtual std::ostream & display (std::ostream &os) const
 Display joint.
Construction and copy and destruction
 Joint (const Transform3f &initialPosition, size_type configSize, size_type numberDof)
 Constructor.
 Joint (const Joint &joint)
 Copy constructor.
virtual JointPtr_t clone () const =0
 Return pointer to copy of this.
virtual ~Joint ()
Name
virtual void name (const std::string &name)
 Set name.
virtual const std::string & name () const
 Get name.
Kinematic chain
JointPtr_t parentJoint () const
 Get a pointer to the parent joint (if any).
void addChildJoint (JointPtr_t joint, bool computePositionInParent=true)
 Add child joint.
std::size_t numberChildJoints () const
 Number of child joints.
JointPtr_t childJoint (std::size_t rank) const
 Get child joint.
const Transform3fpositionInParentFrame () const
 Get position of joint in parent frame.
void positionInParentFrame (const Transform3f &p)
 Set position of joint in parent frame.
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.
value_type lowerBound (size_type rank) const
 Get lower bound of given degree of freedom.
value_type upperBound (size_type rank) const
 Get upper bound of given degree of freedom.
void lowerBound (size_type rank, value_type lowerBound)
 Set lower bound of given degree of freedom.
void upperBound (size_type rank, value_type upperBound)
 Set upper bound of given degree of freedom.
virtual value_type upperBoundLinearVelocity () const =0
 Get upper bound on linear velocity of the joint frame.
virtual value_type upperBoundAngularVelocity () const =0
 Get upper bound on angular velocity of the joint frame.
const value_typemaximalDistanceToParent () const
 Maximal distance of joint origin to parent origin.
Jacobian
const JointJacobian_tjacobian () const
 Get const reference to Jacobian.
JointJacobian_tjacobian ()
 Get non const reference to Jacobian.
Body linked to the joint

Get linked body

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

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.
fcl::Vec3f massCom_
 Mass time center of mass of this and all descendants.
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

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.
hpp::model::Joint::Joint ( const Joint joint)

Copy constructor.

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

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

Member Function Documentation

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.
JointPtr_t hpp::model::Joint::childJoint ( std::size_t  rank) const [inline]

Get child joint.

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

virtual JointPtr_t hpp::model::Joint::clone ( ) const [pure virtual]
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.

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

Return number of degrees of freedom.

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

Display joint.

Joint initial position (when robot is in zero configuration)

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

Get whether given degree of freedom is bounded.

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

Get const reference to Jacobian.

Get non const reference to Jacobian.

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.

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

Set urdf link position in joint frame.

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

Get link name.

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

Set link name.

Get lower bound of given degree of freedom.

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

Set lower bound of given degree of freedom.

Maximal distance of joint origin to parent origin.

virtual void hpp::model::Joint::name ( const std::string &  name) [inline, virtual]

Set name.

virtual const std::string& hpp::model::Joint::name ( ) const [inline, virtual]

Get name.

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.
std::size_t hpp::model::Joint::numberChildJoints ( ) const [inline]

Number of child joints.

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

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

Return number of degrees of freedom.

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

Get position of joint in parent frame.

Set position of joint in parent frame.

Return rank of the joint in the configuration vector.

Return rank of the joint in the velocity vector.

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

Set robot owning the kinematic chain.

Access robot owning the object.

Access robot owning the object.

Set linked body.

Get upper bound of given degree of freedom.

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

Set upper bound of given degree of freedom.

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.

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

friend class CenterOfMassComputation [friend]
friend class ChildrenIterator [friend]
friend class Device [friend]

Member Data Documentation

Mass of this and all descendants.

Mass time center of mass of this and all descendants.

Transform3f hpp::model::Joint::T3f_ [mutable, protected]
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends