Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
hpp::pinocchio::Joint Class Reference

Robot joint. More...

#include <hpp/pinocchio/joint.hh>

Collaboration diagram for hpp::pinocchio::Joint:
[legend]

Public Member Functions

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...
 
LiegroupSpacePtr_t configurationSpace () const
 Get configuration space of joint. More...
 
Construction and copy and destruction
 Joint (DeviceWkPtr_t device, JointIndex indexInJointList)
 Constructor. More...
 
 ~Joint ()
 
Name
const std::string & name () const
 Get name. More...
 
Position
const Transform3fcurrentTransformation () const
 Joint transformation. More...
 
Size and rank
size_type numberDof () const
 Return number of degrees of freedom. More...
 
size_type configSize () const
 Return number of degrees of freedom. More...
 
size_type rankInConfiguration () 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...
 
Kinematic chain
JointPtr_t parentJoint () const
 Get a pointer to the parent joint (if any). 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 (constant) placement of joint in parent frame, i.e. model.jointPlacement[idx]. More...
 
Bounds
void isBounded (size_type rank, bool bounded)
 Set whether given degree of freedom is bounded. More...
 
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...
 
void lowerBounds (vectorIn_t lowerBounds)
 Set lower bounds. More...
 
void upperBounds (vectorIn_t upperBounds)
 Set upper bounds. More...
 
value_type upperBoundLinearVelocity () const
 Get upper bound on linear velocity of the joint frame. More...
 
value_type upperBoundAngularVelocity () const
 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 bool localFrame=true) const
 Get const reference to Jacobian. More...
 
JointJacobian_tjacobian (const bool localFrame=true)
 Get non const reference to Jacobian. More...
 
Body linked to the joint
BodyPtr_t linkedBody () const
 Get linked body. More...
 
Pinocchio API
const JointIndexindex () const
 
const JointModeljointModel () const
 

Protected Member Functions

void computeMaximalDistanceToParent ()
 Compute the maximal distance. More...
 
void setChildList ()
 Store list of childrens. More...
 
Modelmodel ()
 
const Modelmodel () const
 
Datadata ()
 
const Datadata () const
 
void selfAssert () const
 Assert that the members of the struct are valid (no null pointer, etc). More...
 

Protected Attributes

value_type maximalDistanceToParent_
 
DeviceWkPtr_t devicePtr
 
JointJacobian_t jacobian_
 
JointIndex jointIndex
 
std::vector< JointIndexchildren
 

Friends

class Device
 

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()

hpp::pinocchio::Joint::Joint ( DeviceWkPtr_t  device,
JointIndex  indexInJointList 
)

Constructor.

Parameters
devicepointer on the device the joint is belonging to.
indexInJointListindex of the joint, i.e. joint = device.model.joints[index]

◆ ~Joint()

hpp::pinocchio::Joint::~Joint ( )
inline

Member Function Documentation

◆ childJoint()

JointPtr_t hpp::pinocchio::Joint::childJoint ( std::size_t  rank) const

Get child joint.

◆ computeMaximalDistanceToParent()

void hpp::pinocchio::Joint::computeMaximalDistanceToParent ( )
protected

Compute the maximal distance.

See also
maximalDistanceToParent

◆ configSize()

size_type hpp::pinocchio::Joint::configSize ( ) const

Return number of degrees of freedom.

◆ configurationSpace()

LiegroupSpacePtr_t hpp::pinocchio::Joint::configurationSpace ( ) const

Get configuration space of joint.

◆ currentTransformation()

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

Joint transformation.

◆ data() [1/2]

Data& hpp::pinocchio::Joint::data ( )
protected

◆ data() [2/2]

const Data& hpp::pinocchio::Joint::data ( ) const
protected

◆ display()

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

Display joint.

Referenced by hpp::pinocchio::operator<<().

◆ index()

const JointIndex& hpp::pinocchio::Joint::index ( ) const
inline

◆ isBounded() [1/2]

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

Set whether given degree of freedom is bounded.

Warning
Joint always has bounds. When bounded == false, the bounds are -infinity and infinity.

◆ isBounded() [2/2]

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

Get whether given degree of freedom is bounded.

◆ jacobian() [1/2]

const JointJacobian_t& hpp::pinocchio::Joint::jacobian ( const bool  localFrame = true) const

Get const reference to Jacobian.

Parameters
localFrameif true, compute the jacobian (6d) in the local frame, whose linear part corresponds to the velocity of the center of the frame. If false, the jacobian is expressed in the global frame and its linear part corresponds to the value of the velocity vector field at the center of the world.

◆ jacobian() [2/2]

JointJacobian_t& hpp::pinocchio::Joint::jacobian ( const bool  localFrame = true)

Get non const reference to Jacobian.

Parameters
localFrameif true, compute the jacobian (6d) in the local frame, whose linear part corresponds to the velocity of the center of the frame. If false, the jacobian is expressed in the global frame and its linear part corresponds to the value of the velocity vector field at the center of the world.

◆ jointModel()

const JointModel& hpp::pinocchio::Joint::jointModel ( ) const

◆ linkedBody()

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

Get linked body.

◆ lowerBound() [1/2]

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

Get lower bound of given degree of freedom.

◆ lowerBound() [2/2]

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

Set lower bound of given degree of freedom.

◆ lowerBounds()

void hpp::pinocchio::Joint::lowerBounds ( vectorIn_t  lowerBounds)

Set lower bounds.

◆ maximalDistanceToParent()

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

Maximal distance of joint origin to parent origin.

◆ model() [1/2]

Model& hpp::pinocchio::Joint::model ( )
protected

◆ model() [2/2]

const Model& hpp::pinocchio::Joint::model ( ) const
protected

◆ name()

const std::string& hpp::pinocchio::Joint::name ( ) const

Get name.

◆ numberChildJoints()

std::size_t hpp::pinocchio::Joint::numberChildJoints ( ) const

Number of child joints.

◆ numberDof()

size_type hpp::pinocchio::Joint::numberDof ( ) const

Return number of degrees of freedom.

◆ parentJoint()

JointPtr_t hpp::pinocchio::Joint::parentJoint ( ) const

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

◆ positionInParentFrame()

const Transform3f& hpp::pinocchio::Joint::positionInParentFrame ( ) const

Get (constant) placement of joint in parent frame, i.e. model.jointPlacement[idx].

◆ rankInConfiguration()

size_type hpp::pinocchio::Joint::rankInConfiguration ( ) const

Return rank of the joint in the configuration vector.

◆ rankInVelocity()

size_type hpp::pinocchio::Joint::rankInVelocity ( ) const

Return rank of the joint in the velocity vector.

◆ robot() [1/2]

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

Access robot owning the object.

◆ robot() [2/2]

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

Access robot owning the object.

References hpp::pinocchio::display().

◆ selfAssert()

void hpp::pinocchio::Joint::selfAssert ( ) const
protected

Assert that the members of the struct are valid (no null pointer, etc).

◆ setChildList()

void hpp::pinocchio::Joint::setChildList ( )
protected

Store list of childrens.

◆ upperBound() [1/2]

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

Get upper bound of given degree of freedom.

◆ upperBound() [2/2]

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

Set upper bound of given degree of freedom.

◆ upperBoundAngularVelocity()

value_type hpp::pinocchio::Joint::upperBoundAngularVelocity ( ) const

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 = J(\mathbf{q})*\mathbf{\dot{q}}$ is the angular velocity of the joint frame.

◆ upperBoundLinearVelocity()

value_type hpp::pinocchio::Joint::upperBoundLinearVelocity ( ) const

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} = J(\mathbf{q})*\mathbf{\dot{q}} $ is the linear velocity of the joint frame.

◆ upperBounds()

void hpp::pinocchio::Joint::upperBounds ( vectorIn_t  upperBounds)

Set upper bounds.

Friends And Related Function Documentation

◆ Device

friend class Device
friend

Member Data Documentation

◆ children

std::vector<JointIndex> hpp::pinocchio::Joint::children
protected

◆ devicePtr

DeviceWkPtr_t hpp::pinocchio::Joint::devicePtr
protected

◆ jacobian_

JointJacobian_t hpp::pinocchio::Joint::jacobian_
mutableprotected

◆ jointIndex

JointIndex hpp::pinocchio::Joint::jointIndex
protected

◆ maximalDistanceToParent_

value_type hpp::pinocchio::Joint::maximalDistanceToParent_
protected