Robot joint. More...
#include <hpp/model/joint.hh>
Public Member Functions | |
const Transform3f & | initialPosition () const |
Joint initial position (when robot is in zero configuration) | |
const Transform3f & | currentTransformation () 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_type & | numberDof () const |
Return number of degrees of freedom. | |
const size_type & | configSize () const |
Return number of degrees of freedom. | |
const 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. | |
JointConfiguration * | configuration () 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 Transform3f & | positionInParentFrame () 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_type & | maximalDistanceToParent () const |
Maximal distance of joint origin to parent origin. | |
Jacobian | |
const JointJacobian_t & | jacobian () const |
Get const reference to Jacobian. | |
JointJacobian_t & | jacobian () |
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 Transform3f & | linkInJointFrame () 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 | |
JointConfiguration * | configuration_ |
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 |
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.
hpp::model::Joint::Joint | ( | const Transform3f & | initialPosition, |
size_type | configSize, | ||
size_type | numberDof | ||
) |
Constructor.
initialPosition | position of the joint before being inserted in a kinematic chain, |
configSize | dimension of the configuration vector, |
numberDof | dimension 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] |
void hpp::model::Joint::addChildJoint | ( | JointPtr_t | joint, |
bool | computePositionInParent = true |
||
) |
Add child joint.
joint | child joint added to this one, |
computePositionInParent | whether to compute position of the child joint in this one's frame. |
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] |
Return pointer to copy of this.
Clone body and therefore inner and outer objects (see Body::clone).
Implemented in hpp::model::JointTranslation< dimension >, hpp::model::jointRotation::Bounded, hpp::model::jointRotation::UnBounded, hpp::model::JointRotation, hpp::model::JointSO3, and hpp::model::JointAnchor.
virtual void hpp::model::Joint::computeMaximalDistanceToParent | ( | ) | [protected, pure virtual] |
virtual void hpp::model::Joint::computePosition | ( | ConfigurationIn_t | configuration, |
const Transform3f & | parentPosition, | ||
Transform3f & | position | ||
) | const [pure virtual] |
Compute position of joint.
configuration | the configuration of the robot, |
parentPosition | position of parent joint, |
position | position 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.
JointConfiguration* hpp::model::Joint::configuration | ( | ) | const [inline] |
const Transform3f& hpp::model::Joint::currentTransformation | ( | ) | const |
Joint transformation.
virtual std::ostream& hpp::model::Joint::display | ( | std::ostream & | os | ) | const [virtual] |
Display joint.
const Transform3f& hpp::model::Joint::initialPosition | ( | ) | const |
Joint initial position (when robot is in zero configuration)
void hpp::model::Joint::isBounded | ( | size_type | rank, |
bool | bounded | ||
) |
bool hpp::model::Joint::isBounded | ( | size_type | rank | ) | const |
Get whether given degree of freedom is bounded.
const JointJacobian_t& hpp::model::Joint::jacobian | ( | ) | const [inline] |
Get const reference to Jacobian.
JointJacobian_t& hpp::model::Joint::jacobian | ( | ) | [inline] |
Get non const reference to Jacobian.
BodyPtr_t hpp::model::Joint::linkedBody | ( | ) | const |
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.
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.
value_type hpp::model::Joint::lowerBound | ( | size_type | rank | ) | const |
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.
const value_type& hpp::model::Joint::maximalDistanceToParent | ( | ) | const [inline] |
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.
vector_t hpp::model::Joint::neutralConfiguration | ( | ) | const [inline] |
Get neutral configuration of joint.
Neutral configuration is
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.
JointPtr_t hpp::model::Joint::parentJoint | ( | ) | const [inline] |
Get a pointer to the parent joint (if any).
const Transform3f& hpp::model::Joint::positionInParentFrame | ( | ) | const [inline] |
Get position of joint in parent frame.
void hpp::model::Joint::positionInParentFrame | ( | const Transform3f & | p | ) | [inline] |
Set position of joint in parent frame.
const size_type& hpp::model::Joint::rankInConfiguration | ( | ) | const [inline] |
Return rank of the joint in the configuration vector.
size_type hpp::model::Joint::rankInVelocity | ( | ) | const [inline] |
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.
DeviceConstPtr_t hpp::model::Joint::robot | ( | ) | const [inline] |
Access robot owning the object.
DevicePtr_t hpp::model::Joint::robot | ( | ) | [inline] |
Access robot owning the object.
void hpp::model::Joint::setLinkedBody | ( | const BodyPtr_t & | body | ) |
Set linked body.
value_type hpp::model::Joint::upperBound | ( | size_type | rank | ) | const |
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.
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.
Implemented in hpp::model::JointTranslation< dimension >, hpp::model::JointRotation, hpp::model::JointSO3, and hpp::model::JointAnchor.
friend class CenterOfMassComputation [friend] |
friend class ChildrenIterator [friend] |
friend class Device [friend] |
JointConfiguration* hpp::model::Joint::configuration_ [protected] |
Transform3f hpp::model::Joint::currentTransformation_ [mutable, protected] |
Transform3f hpp::model::Joint::linkInJointFrame_ [protected] |
value_type hpp::model::Joint::mass_ [protected] |
Mass of this and all descendants.
fcl::Vec3f hpp::model::Joint::massCom_ [protected] |
Mass time center of mass of this and all descendants.
vector_t hpp::model::Joint::neutralConfiguration_ [protected] |
Transform3f hpp::model::Joint::positionInParentFrame_ [protected] |
Transform3f hpp::model::Joint::T3f_ [mutable, protected] |