#include <hpp/model/joint-configuration.hh>
List of all members.
Public Member Functions |
| UnBounded () |
virtual | ~UnBounded () |
void | interpolate (ConfigurationIn_t q1, ConfigurationIn_t q2, const value_type &u, const size_type &index, ConfigurationOut_t result) |
| Interpolate two configurations of the joint.
|
value_type | distance (ConfigurationIn_t q1, ConfigurationIn_t q2, const size_type &index) const |
| Distance between two configurations of the joint.
|
void | integrate (ConfigurationIn_t q, vectorIn_t v, const size_type &indexConfig, const size_type &indexVelocity, ConfigurationOut_t result) const |
| Integrate constant derivative during unit time.
|
void | difference (ConfigurationIn_t q1, ConfigurationIn_t q2, const size_type &indexConfig, const size_type &indexVelocity, vectorOut_t result) const |
| Difference between two configurations.
|
void | uniformlySample (const size_type &index, ConfigurationOut_t result) const |
| Uniformly sample the configuration space of the joint.
|
Constructor & Destructor Documentation
Member Function Documentation
Difference between two configurations.
- Parameters:
-
q1 | configuration, |
q2 | configuration, |
indexConfig | index of first component of q corresponding to the joint. |
indexVelocity | index of first component of v corresponding to the joint |
- Return values:
-
result[indexVelocity:indexVelocity+nbdofs] | part of vector representing the difference between q1 and q2. |
See derived classes for details
Implements hpp::model::JointConfiguration.
Distance between two configurations of the joint.
- Parameters:
-
q1,q2 | two configurations of the robot |
index | index of first component of q1 and q2 corresponding to the joint. |
Implements hpp::model::JointConfiguration.
Integrate constant derivative during unit time.
- Parameters:
-
q | initial configuration |
v | joint velocity |
indexConfig | index of first component of q corresponding to the joint. |
indexVelocity | index of first component of v corresponding to the joint |
- Return values:
-
result | write joint configuration in result [indexConfig:indexConfig + joint config size] |
- Note:
- if result is beying bounds, return active bound.
Implements hpp::model::JointConfiguration.
Interpolate two configurations of the joint.
- Parameters:
-
q1,q2,two | configurations to interpolate |
u | in [0,1] position along the interpolation: q1 for u=0, q2 for u=1 |
index | index of first component of q1 and q2 corresponding to the joint. |
- Return values:
-
result | write 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.
Uniformly sample the configuration space of the joint.
- Parameters:
-
index | index of first component of q corresponding to the joint. |
- Return values:
-
result | write joint configuration in result [index:index+nb dofs] |
Implements hpp::model::JointConfiguration.