#include <hpp/model/joint.hh>
Public Member Functions | |
JointRotation (const Transform3f &initialPosition, size_type configSize, size_type numberDof) | |
Constructor. | |
JointRotation (const JointRotation &joint) | |
virtual JointPtr_t | clone () const =0 |
Return pointer to copy of this Clone body and therefore inner and outer objects (see Body::clone). | |
virtual void | computePosition (ConfigurationIn_t configuration, const Transform3f &parentPosition, Transform3f &position) const =0 |
Compute position of joint. | |
virtual | ~JointRotation () |
virtual value_type | upperBoundLinearVelocity () const |
Get upper bound on linear velocity of the joint frame. | |
virtual value_type | upperBoundAngularVelocity () const |
Get upper bound on angular velocity of the joint frame. | |
Protected Member Functions | |
virtual void | computeMaximalDistanceToParent () |
Protected Attributes | |
fcl::Matrix3f | R_ |
fcl::Vec3f | axis_ |
fcl::Vec3f | O2O1_ |
fcl::Vec3f | cross_ |
fcl::Vec3f | com_ |
Rotation Joint.
Map an angle as one-dimensional input vector to a rotation around a fixed axis in parent frame.
hpp::model::JointRotation::JointRotation | ( | const Transform3f & | initialPosition, |
size_type | configSize, | ||
size_type | numberDof | ||
) |
Constructor.
initialPosition | position of the joint in global frame before being linked to a parent, |
configSize | dimension of the configuration vector, |
numberDof | dimension of the velocity vector. |
hpp::model::JointRotation::JointRotation | ( | const JointRotation & | joint | ) |
virtual hpp::model::JointRotation::~JointRotation | ( | ) | [virtual] |
virtual JointPtr_t hpp::model::JointRotation::clone | ( | ) | const [pure virtual] |
Return pointer to copy of this Clone body and therefore inner and outer objects (see Body::clone).
Implements hpp::model::Joint.
Implemented in hpp::model::jointRotation::Bounded, and hpp::model::jointRotation::UnBounded.
virtual void hpp::model::JointRotation::computeMaximalDistanceToParent | ( | ) | [protected, virtual] |
Implements hpp::model::Joint.
virtual void hpp::model::JointRotation::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. |
Implements hpp::model::Joint.
Implemented in hpp::model::jointRotation::Bounded, and hpp::model::jointRotation::UnBounded.
virtual value_type hpp::model::JointRotation::upperBoundAngularVelocity | ( | ) | const [inline, virtual] |
virtual value_type hpp::model::JointRotation::upperBoundLinearVelocity | ( | ) | const [inline, virtual] |
fcl::Vec3f hpp::model::JointRotation::axis_ [mutable, protected] |
fcl::Vec3f hpp::model::JointRotation::com_ [mutable, protected] |
fcl::Vec3f hpp::model::JointRotation::cross_ [mutable, protected] |
fcl::Vec3f hpp::model::JointRotation::O2O1_ [mutable, protected] |
fcl::Matrix3f hpp::model::JointRotation::R_ [mutable, protected] |