hpp::model::RotationJointConfig Class Reference

Configuration of a JointRotation. More...

#include <hpp/model/joint-configuration.hh>

Inheritance diagram for hpp::model::RotationJointConfig:
Collaboration diagram for hpp::model::RotationJointConfig:

List of all members.

Public Member Functions

 RotationJointConfig (size_type configSize)
 Constructor.
virtual ~RotationJointConfig ()
virtual void interpolate (ConfigurationIn_t q1, ConfigurationIn_t q2, const value_type &u, const size_type &index, ConfigurationOut_t result)=0
 Interpolate two configurations of the joint.
virtual value_type distance (ConfigurationIn_t q1, ConfigurationIn_t q2, const size_type &index) const =0
 Distance between two configurations of the joint.
virtual void integrate (ConfigurationIn_t q, vectorIn_t v, const size_type &indexConfig, const size_type &indexVelocity, ConfigurationOut_t result) const =0
 Integrate constant derivative during unit time.
virtual void difference (ConfigurationIn_t q1, ConfigurationIn_t q2, const size_type &indexConfig, const size_type &indexVelocity, vectorOut_t result) const =0
 Difference between two configurations.
virtual void uniformlySample (const size_type &index, ConfigurationOut_t result) const =0
 Uniformly sample the configuration space of the joint.

Detailed Description

Configuration of a JointRotation.


Constructor & Destructor Documentation

Constructor.

Parameters:
configSizedimension of the joint configuration size: used to resize the vector of bounds.

Member Function Documentation

virtual void hpp::model::RotationJointConfig::difference ( ConfigurationIn_t  q1,
ConfigurationIn_t  q2,
const size_type indexConfig,
const size_type indexVelocity,
vectorOut_t  result 
) const [pure virtual]

Difference between two configurations.

Parameters:
q1configuration,
q2configuration,
indexConfigindex of first component of q corresponding to the joint.
indexVelocityindex of first component of v corresponding to the joint
Return values:
result[indexVelocity]component of vector representing the difference between q1 and q2.

If joint is bounded:

\[ \texttt{result}[\texttt{index}] = \textbf{q}_1[\texttt{index}] - \textbf{q}_2[\texttt{index}] \]

If joint is not bounded:

\[ \texttt{result}[\texttt{index}] = \textbf{q}_1[\texttt{index}] - \textbf{q}_2[\texttt{index}] + 2k\pi \]

where $k$ is such that $\texttt{result}[\texttt{index}]$ lies between $-\pi$ and $\pi$.

Implements hpp::model::JointConfiguration.

virtual value_type hpp::model::RotationJointConfig::distance ( ConfigurationIn_t  q1,
ConfigurationIn_t  q2,
const size_type index 
) const [pure virtual]

Distance between two configurations of the joint.

Parameters:
q1,q2two configurations of the robot
indexindex of first component of q1 and q2 corresponding to the joint.
Returns:
the angle between the joint orientations

Implements hpp::model::JointConfiguration.

virtual void hpp::model::RotationJointConfig::integrate ( ConfigurationIn_t  q,
vectorIn_t  v,
const size_type indexConfig,
const size_type indexVelocity,
ConfigurationOut_t  result 
) const [pure virtual]

Integrate constant derivative during unit time.

Parameters:
qinitial configuration
vjoint velocity
indexConfigindex of first component of q corresponding to the joint.
indexVelocityindex of first component of v corresponding to the joint
Return values:
resultwrite joint configuration in result [indexConfig:indexConfig + joint config size]
Note:
if result is beying bounds, return active bound.

Implements hpp::model::JointConfiguration.

virtual void hpp::model::RotationJointConfig::interpolate ( ConfigurationIn_t  q1,
ConfigurationIn_t  q2,
const value_type u,
const size_type index,
ConfigurationOut_t  result 
) [pure virtual]

Interpolate two configurations of the joint.

Parameters:
q1,q2,twoconfigurations to interpolate
uin [0,1] position along the interpolation: q1 for u=0, q2 for u=1
indexindex of first component of q1 and q2 corresponding to the joint.
Return values:
resultwrite joint configuration in result [index:index+nb dofs]

q1 and q2 are configurations of the robot where coordinates between index and index + number of dofs - 1 correspond to the configuration of the joint:

  • a real value for translation joint and bounded rotation joints,
  • an angle for unbounded rotation joints,
  • x, y, z, roll, pitch, yaw for freeflyer joints.

Implements hpp::model::JointConfiguration.

virtual void hpp::model::RotationJointConfig::uniformlySample ( const size_type index,
ConfigurationOut_t  result 
) const [pure virtual]

Uniformly sample the configuration space of the joint.

Parameters:
indexindex of first component of q corresponding to the joint.
Return values:
resultwrite joint configuration in result [index:index+nb dofs]

Implements hpp::model::JointConfiguration.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends