hpp-pinocchio
4.9.1
Wrapping of the kinematic/dynamic chain Pinocchio for HPP.
|
#include <hpp/pinocchio/joint.hh>
Public Member Functions | |
DeviceConstPtr_t | robot () const |
Access robot owning the object. More... | |
DevicePtr_t | robot () |
Access robot owning the object. More... | |
std::ostream & | display (std::ostream &os) const |
Display joint. More... | |
LiegroupSpacePtr_t | configurationSpace () const |
Get configuration space of joint. More... | |
LiegroupSpacePtr_t | RnxSOnConfigurationSpace () const |
Name | |
const std::string & | name () const |
Get name. More... | |
Position | |
const Transform3f & | currentTransformation () const |
Joint transformation. More... | |
const Transform3f & | currentTransformation (const DeviceData &data) 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 Transform3f & | positionInParentFrame () const |
Get (constant) placement of joint in parent frame, i.e. model.jointPlacement[idx]. More... | |
Bounds | |
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... | |
void | lowerBounds (vectorIn_t lowerBounds) |
Set lower bounds. More... | |
void | upperBounds (vectorIn_t upperBounds) |
Set upper bounds. More... | |
value_type | upperBoundLinearVelocity () const |
value_type | upperBoundAngularVelocity () const |
const value_type & | maximalDistanceToParent () const |
Maximal distance of joint origin to parent origin. More... | |
Jacobian | |
JointJacobian_t & | jacobian (const bool localFrame=true) const |
JointJacobian_t & | jacobian (DeviceData &data, const bool localFrame=true) const |
Body linked to the joint | |
BodyPtr_t | linkedBody () const |
Get linked body. More... | |
Pinocchio API | |
const JointIndex & | index () const |
const JointModel & | jointModel () const |
Protected Member Functions | |
void | computeMaximalDistanceToParent () |
Compute the maximal distance. More... | |
void | setChildList () |
Store list of childrens. More... | |
Model & | model () |
const Model & | model () const |
DeviceData & | data () 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 |
JointIndex | jointIndex |
std::vector< JointIndex > | children |
Friends | |
class | Device |
Construction and copy and destruction | |
static JointPtr_t | create (DeviceWkPtr_t device, JointIndex indexInJointList) |
Joint (DeviceWkPtr_t device, JointIndex indexInJointList) | |
~Joint () | |
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
This class is a wrapper to pinocchio::JointModelTpl.
hpp::pinocchio::Joint::Joint | ( | DeviceWkPtr_t | device, |
JointIndex | indexInJointList | ||
) |
Constructor
indexInJointList | index in pinocchio vector of joints (pinocchio::ModelTpl::joints). Should be > 0. |
|
inline |
JointPtr_t hpp::pinocchio::Joint::childJoint | ( | std::size_t | rank | ) | const |
Get child joint.
|
protected |
Compute the maximal distance.
size_type hpp::pinocchio::Joint::configSize | ( | ) | const |
Return number of degrees of freedom.
LiegroupSpacePtr_t hpp::pinocchio::Joint::configurationSpace | ( | ) | const |
Get configuration space of joint.
|
static |
Create a new joint
indexInJointList | index in pinocchio vector of joints (pinocchio::ModelTpl::joints) |
|
inline |
Joint transformation.
const Transform3f& hpp::pinocchio::Joint::currentTransformation | ( | const DeviceData & | data | ) | const |
Joint transformation.
|
protected |
std::ostream& hpp::pinocchio::Joint::display | ( | std::ostream & | os | ) | const |
Display joint.
|
inline |
void hpp::pinocchio::Joint::isBounded | ( | size_type | rank, |
bool | bounded | ||
) |
Set whether given degree of freedom is bounded
bounded == false
, the bounds are -infinity
and infinity
. bool hpp::pinocchio::Joint::isBounded | ( | size_type | rank | ) | const |
Get whether given degree of freedom is bounded.
|
inline |
Get non const reference to Jacobian
localFrame | if 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. |
JointJacobian_t& hpp::pinocchio::Joint::jacobian | ( | DeviceData & | data, |
const bool | localFrame = true |
||
) | const |
Get reference to Jacobian
data | a DeviceData (see hpp::pinocchio::DeviceSync for details). |
localFrame | if 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. |
const JointModel& hpp::pinocchio::Joint::jointModel | ( | ) | const |
BodyPtr_t hpp::pinocchio::Joint::linkedBody | ( | ) | const |
Get linked body.
value_type hpp::pinocchio::Joint::lowerBound | ( | size_type | rank | ) | const |
Get lower bound of given degree of freedom.
void hpp::pinocchio::Joint::lowerBound | ( | size_type | rank, |
value_type | lowerBound | ||
) |
Set lower bound of given degree of freedom.
void hpp::pinocchio::Joint::lowerBounds | ( | vectorIn_t | lowerBounds | ) |
Set lower bounds.
|
inline |
Maximal distance of joint origin to parent origin.
|
protected |
|
protected |
const std::string& hpp::pinocchio::Joint::name | ( | ) | const |
Get name.
std::size_t hpp::pinocchio::Joint::numberChildJoints | ( | ) | const |
Number of child joints.
size_type hpp::pinocchio::Joint::numberDof | ( | ) | const |
Return number of degrees of freedom.
JointPtr_t hpp::pinocchio::Joint::parentJoint | ( | ) | const |
Get a pointer to the parent joint (if any).
const Transform3f& hpp::pinocchio::Joint::positionInParentFrame | ( | ) | const |
Get (constant) placement of joint in parent frame, i.e. model.jointPlacement[idx].
size_type hpp::pinocchio::Joint::rankInConfiguration | ( | ) | const |
Return rank of the joint in the configuration vector.
size_type hpp::pinocchio::Joint::rankInVelocity | ( | ) | const |
Return rank of the joint in the velocity vector.
LiegroupSpacePtr_t hpp::pinocchio::Joint::RnxSOnConfigurationSpace | ( | ) | const |
Get configuration space of joint. Use R^n x SO(n) instead of SE(n).
|
inline |
Access robot owning the object.
|
inline |
Access robot owning the object.
|
protected |
Assert that the members of the struct are valid (no null pointer, etc).
|
protected |
Store list of childrens.
value_type hpp::pinocchio::Joint::upperBound | ( | size_type | rank | ) | const |
Get upper bound of given degree of freedom.
void hpp::pinocchio::Joint::upperBound | ( | size_type | rank, |
value_type | upperBound | ||
) |
Set upper bound of given degree of freedom.
value_type hpp::pinocchio::Joint::upperBoundAngularVelocity | ( | ) | const |
Get upper bound on angular velocity of the joint frame
where
value_type hpp::pinocchio::Joint::upperBoundLinearVelocity | ( | ) | const |
Get upper bound on linear velocity of the joint frame
where
void hpp::pinocchio::Joint::upperBounds | ( | vectorIn_t | upperBounds | ) |
Set upper bounds.
|
friend |
|
protected |
|
protected |
|
protected |
|
protected |