hpp-pinocchio 7.0.0
Wrapping of the kinematic/dynamic chain Pinocchio for HPP.
Loading...
Searching...
No Matches
hpp::pinocchio::Joint Class Reference

#include <hpp/pinocchio/joint.hh>

Public Member Functions

DeviceConstPtr_t robot () const
 Access robot owning the object.
DevicePtr_t robot ()
 Access robot owning the object.
std::ostream & display (std::ostream &os) const
 Display joint.
LiegroupSpacePtr_t configurationSpace () const
 Get configuration space of joint.
LiegroupSpacePtr_t RnxSOnConfigurationSpace () const
bool operator== (const Joint &other) const
bool operator!= (const Joint &other) const
Name
const std::string & name () const
 Get name.
Position
const Transform3scurrentTransformation () const
 Joint transformation.
const Transform3scurrentTransformation (const DeviceData &data) const
 Joint transformation.
Size and rank
size_type numberDof () const
 Return number of degrees of freedom.
size_type configSize () const
 Return number of degrees of freedom.
size_type rankInConfiguration () const
 Return rank of the joint in the configuration vector.
size_type rankInVelocity () const
 Return rank of the joint in the velocity vector.
Kinematic chain
JointPtr_t parentJoint () const
 Get a pointer to the parent joint (if any).
std::size_t numberChildJoints () const
 Number of child joints.
JointPtr_t childJoint (std::size_t rank) const
 Get child joint.
const Transform3spositionInParentFrame () const
Bounds
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.
void lowerBounds (vectorIn_t lowerBounds)
 Set lower bounds.
void upperBounds (vectorIn_t upperBounds)
 Set upper bounds.
value_type upperBoundLinearVelocity () const
value_type upperBoundAngularVelocity () const
const value_typemaximalDistanceToParent ()
 Maximal distance of joint origin to parent origin.
Jacobian
JointJacobian_tjacobian (const bool localFrame=true) const
JointJacobian_tjacobian (DeviceData &data, const bool localFrame=true) const
Body linked to the joint
BodyPtr_t linkedBody () const
 Get linked body.

Protected Member Functions

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

Protected Attributes

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

Friends

class Device

Construction and copy and destruction

static JointPtr_t create (DeviceWkPtr_t device, JointIndex indexInJointList)
 Joint (DeviceWkPtr_t device, JointIndex indexInJointList)
 ~Joint ()

Pinocchio API

static size_type index (const JointConstPtr_t &joint)
const JointIndexindex () const
const JointModeljointModel () const

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 an element of a Lie group, either

  • a vector space for JointTranslation, and bounded JointRotation,
  • the unit circle for non-bounded JointRotation joints,
  • an element of SO(3) for JointSO3, represented by a unit quaternion.

This class is a wrapper to pinocchio::JointModelTpl.

Constructor & Destructor Documentation

◆ Joint() [1/2]

hpp::pinocchio::Joint::Joint(DeviceWkPtr_tdevice,
JointIndexindexInJointList )

Constructor

Parameters
indexInJointListindex in pinocchio vector of joints (pinocchio::ModelTpl::joints). Should be > 0.
Note
indices of device start at 1 since 0 corresponds to "universe".

◆ ~Joint()

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

◆ Joint() [2/2]

hpp::pinocchio::Joint::Joint()
inlineprotected

Member Function Documentation

◆ childJoint()

JointPtr_t hpp::pinocchio::Joint::childJoint(std::size_trank)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.

◆ create()

JointPtr_t hpp::pinocchio::Joint::create(DeviceWkPtr_tdevice,
JointIndexindexInJointList )
static

Create a new joint

Parameters
indexInJointListindex in pinocchio vector of joints (pinocchio::ModelTpl::joints)
Returns
shared pointer to result if indexInJointList > 0, empty shared pointer if indexInJointList == 0.
Note
indices of device start at 1 since 0 corresponds to "universe".

◆ currentTransformation() [1/2]

const Transform3s & hpp::pinocchio::Joint::currentTransformation()const
inline

Joint transformation.

◆ currentTransformation() [2/2]

const Transform3s & hpp::pinocchio::Joint::currentTransformation(const DeviceData &data)const

Joint transformation.

◆ data()

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

◆ display()

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

Display joint.

◆ HPP_SERIALIZABLE()

hpp::pinocchio::Joint::HPP_SERIALIZABLE()
protected

◆ index() [1/2]

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

◆ index() [2/2]

size_type hpp::pinocchio::Joint::index(const JointConstPtr_t &joint)
inlinestatic

Get the index for a given joint

Returns
0 if joint is NULL ("universe"), joint->index() otherwise.

◆ isBounded() [1/2]

bool hpp::pinocchio::Joint::isBounded(size_typerank)const

Get whether given degree of freedom is bounded.

◆ isBounded() [2/2]

void hpp::pinocchio::Joint::isBounded(size_typerank,
boolbounded )

Set whether given degree of freedom is bounded

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

◆ jacobian() [1/2]

JointJacobian_t & hpp::pinocchio::Joint::jacobian(const boollocalFrame = true)const
inline

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.

◆ jacobian() [2/2]

JointJacobian_t & hpp::pinocchio::Joint::jacobian(DeviceData &data,
const boollocalFrame = true ) const

Get reference to Jacobian

Parameters
dataa DeviceData (see hpp::pinocchio::DeviceSync for details).
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_typerank)const

Get lower bound of given degree of freedom.

◆ lowerBound() [2/2]

void hpp::pinocchio::Joint::lowerBound(size_typerank,
value_typelowerBound )

Set lower bound of given degree of freedom.

◆ lowerBounds()

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

Set lower bounds.

◆ maximalDistanceToParent()

const value_type & hpp::pinocchio::Joint::maximalDistanceToParent()
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.

◆ operator!=()

bool hpp::pinocchio::Joint::operator!=(const Joint &other)const
inline

◆ operator==()

bool hpp::pinocchio::Joint::operator==(const Joint &other)const
inline

◆ parentJoint()

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

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

◆ positionInParentFrame()

const Transform3s & 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.

◆ RnxSOnConfigurationSpace()

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

Get configuration space of joint. Use R^n x SO(n) instead of SE(n).

◆ robot() [1/2]

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

Access robot owning the object.

◆ robot() [2/2]

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

Access robot owning the object.

◆ 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_typerank)const

Get upper bound of given degree of freedom.

◆ upperBound() [2/2]

void hpp::pinocchio::Joint::upperBound(size_typerank,
value_typeupperBound )

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

Set upper bounds.

◆ 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

◆ jointIndex

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

◆ maximalDistanceToParent_

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

The documentation for this class was generated from the following file: