hpp::model::JointSO3 Class Reference

Spherical Joint. More...

#include <hpp/model/joint.hh>

Inheritance diagram for hpp::model::JointSO3:
Collaboration diagram for hpp::model::JointSO3:

List of all members.

Public Member Functions

 JointSO3 (const Transform3f &initialPosition)
 JointSO3 (const JointSO3 &joint)
virtual JointPtr_t clone () const
 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
 Compute position of joint.
virtual ~JointSO3 ()
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 ()

Detailed Description

Spherical Joint.

map a unit quaternion as input vector to a rotation of SO(3).


Constructor & Destructor Documentation

hpp::model::JointSO3::JointSO3 ( const Transform3f initialPosition)
virtual hpp::model::JointSO3::~JointSO3 ( ) [virtual]

Member Function Documentation

virtual JointPtr_t hpp::model::JointSO3::clone ( ) const [virtual]

Return pointer to copy of this Clone body and therefore inner and outer objects (see Body::clone).

Implements hpp::model::Joint.

virtual void hpp::model::JointSO3::computeMaximalDistanceToParent ( ) [protected, virtual]

Implements hpp::model::Joint.

virtual void hpp::model::JointSO3::computePosition ( ConfigurationIn_t  configuration,
const Transform3f parentPosition,
Transform3f position 
) const [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.

virtual value_type hpp::model::JointSO3::upperBoundAngularVelocity ( ) const [inline, virtual]

Get upper bound on angular velocity of the joint frame.

Returns:
1

Implements hpp::model::Joint.

virtual value_type hpp::model::JointSO3::upperBoundLinearVelocity ( ) const [inline, virtual]

Get upper bound on linear velocity of the joint frame.

Returns:
0

Implements hpp::model::Joint.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends