hpp::model::JointAnchor Class Reference

Anchor Joint. More...

#include <hpp/model/joint.hh>

Inheritance diagram for hpp::model::JointAnchor:
Collaboration diagram for hpp::model::JointAnchor:

List of all members.

Public Member Functions

 JointAnchor (const Transform3f &initialPosition)
 JointAnchor (const JointAnchor &joint)
virtual JointPtr_t clone () const
 Return pointer to copy of this Clone body and therefore inner and outer objects (see Body::clone).
virtual ~JointAnchor ()
virtual void computePosition (ConfigurationIn_t configuration, const Transform3f &parentPosition, Transform3f &position) const
 Compute position of joint.
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

Anchor Joint.

An anchor joint has no degree of freedom. It is usually used as an intermediate frame in a kinematic chain, or as a root joint for a multi-robot kinematic chain.


Constructor & Destructor Documentation

hpp::model::JointAnchor::JointAnchor ( const Transform3f initialPosition)

Member Function Documentation

virtual JointPtr_t hpp::model::JointAnchor::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::JointAnchor::computeMaximalDistanceToParent ( ) [protected, virtual]

Implements hpp::model::Joint.

virtual void hpp::model::JointAnchor::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.

Get upper bound on angular velocity of the joint frame.

Returns:
0

Implements hpp::model::Joint.

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