hpp::model::JointRotation Class Reference

Rotation Joint. More...

#include <hpp/model/joint.hh>

Inheritance diagram for hpp::model::JointRotation:
Collaboration diagram for hpp::model::JointRotation:

List of all members.

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_

Detailed Description

Rotation Joint.

Map an angle as one-dimensional input vector to a rotation around a fixed axis in parent frame.


Constructor & Destructor Documentation

hpp::model::JointRotation::JointRotation ( const Transform3f initialPosition,
size_type  configSize,
size_type  numberDof 
)

Constructor.

Parameters:
initialPositionposition of the joint in global frame before being linked to a parent,
configSizedimension of the configuration vector,
numberDofdimension of the velocity vector.

Member Function Documentation

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.

Parameters:
configurationthe configuration of the robot,
parentPositionposition of parent joint,
Return values:
positionposition of this joint.

Implements hpp::model::Joint.

Implemented in hpp::model::jointRotation::Bounded, and hpp::model::jointRotation::UnBounded.

Get upper bound on angular velocity of the joint frame.

Returns:
1

Implements hpp::model::Joint.

Get upper bound on linear velocity of the joint frame.

Returns:
0

Implements hpp::model::Joint.


Member Data Documentation

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends