hpp::model::JointTranslation< dimension > Class Template Reference

Translation Joint. More...

#include <hpp/model/joint.hh>

Inheritance diagram for hpp::model::JointTranslation< dimension >:
Collaboration diagram for hpp::model::JointTranslation< dimension >:

List of all members.

Public Member Functions

 JointTranslation (const Transform3f &initialPosition)
 JointTranslation (const JointTranslation< dimension > &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 ~JointTranslation ()
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

template<size_type dimension>
class hpp::model::JointTranslation< dimension >

Translation Joint.

Map a 1,2 or 3-dimensional input vector to a translation


Constructor & Destructor Documentation

template<size_type dimension>
hpp::model::JointTranslation< dimension >::JointTranslation ( const Transform3f initialPosition)
template<size_type dimension>
hpp::model::JointTranslation< dimension >::JointTranslation ( const JointTranslation< dimension > &  joint)
template<size_type dimension>
virtual hpp::model::JointTranslation< dimension >::~JointTranslation ( ) [virtual]

Member Function Documentation

template<size_type dimension>
virtual JointPtr_t hpp::model::JointTranslation< dimension >::clone ( ) const [virtual]

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

Implements hpp::model::Joint.

template<size_type dimension>
virtual void hpp::model::JointTranslation< dimension >::computeMaximalDistanceToParent ( ) [protected, virtual]

Implements hpp::model::Joint.

template<size_type dimension>
virtual void hpp::model::JointTranslation< dimension >::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.

template<size_type dimension>
virtual value_type hpp::model::JointTranslation< dimension >::upperBoundAngularVelocity ( ) const [inline, virtual]

Get upper bound on angular velocity of the joint frame.

Returns:
0

Implements hpp::model::Joint.

template<size_type dimension>
virtual value_type hpp::model::JointTranslation< dimension >::upperBoundLinearVelocity ( ) const [inline, virtual]

Get upper bound on linear velocity of the joint frame.

Returns:
1

Implements hpp::model::Joint.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends