List of all members.
Public Types |
enum | joint_type { hinge_type,
slider_type,
ball_type
} |
typedef
base_bone_traits::transform_type | transform_type |
typedef
base_bone_traits::vector3_type | vector3_type |
typedef
base_bone_traits::math_types::real_type | real_type |
typedef
base_bone_traits::math_types::value_traits | value_traits |
Public Member Functions |
| BoneTraits () |
joint_type const & | type () const |
joint_type & | type () |
vector3_type const & | u () const |
vector3_type & | u () |
real_type const & | theta (size_t const &i) const |
real_type & | theta (size_t const &i) |
size_t | active_dofs () const |
real_type const & | min_joint_limit (size_t const &i) const |
real_type & | min_joint_limit (size_t const &i) |
real_type const & | max_joint_limit (size_t const &i) const |
real_type & | max_joint_limit (size_t const &i) |
Static Public Member Functions |
template<typename bone_type , typename chain_type , typename matrix_range > |
static void | compute_jacobian (bone_type &bone, chain_type &chain, matrix_range &J) |
template<typename bone_type , typename vector_range > |
static void | set_theta (bone_type &bone, vector_range const &sub_theta) |
template<typename bone_type , typename vector_range > |
static void | get_theta (bone_type const &bone, vector_range &sub_theta) |
template<typename bone_type , typename vector_range > |
static void | get_joint_limits (bone_type const &bone, vector_range &sub_min, vector_range &sub_max) |
template<typename bone_type , typename vector_range > |
static void | joint_limit_projection (bone_type const &bone, vector_range &sub_theta) |
Protected Attributes |
joint_type | m_type |
| The joint type that this bone is connected to its parent bone with.
|
real_type | m_theta [6] |
| Joint parameter values.
|
real_type | m_min_theta [6] |
| Minimum joint parameter value.
|
real_type | m_max_theta [6] |
| Maximum joint parameter value.
|
vector3_type | m_u |
| Unit joint axis, given as a constant vector in parent frame.
|
Detailed Description
template<typename base_bone_traits>
class OpenTissue::kinematics::inverse::BoneTraits< base_bone_traits >
Default Bone Traits for Inverse Kinematics. This class provides functionality to handle constrained inverse kinematics.
- Warning:
- If end-users wants to extend with their own bone traits then their bone traits must comply with a similar interface as this bone traits class has.
- Template Parameters:
-
| base_bone_traits | A base bone traits. This could for instance be the default bone traits from the skeleton library. This traits class must define the types of transforms and different ways of manipulating and doing calculations with these types. Thus this bone trait class does not care about what kind of coordinate representation one wants to use for the skeleton/bone transformations. |
Member Typedef Documentation
template<typename base_bone_traits >
template<typename base_bone_traits >
template<typename base_bone_traits >
template<typename base_bone_traits >
Member Enumeration Documentation
template<typename base_bone_traits >
- Enumerator:
hinge_type |
|
slider_type |
|
ball_type |
|
Constructor & Destructor Documentation
template<typename base_bone_traits >
Member Function Documentation
template<typename base_bone_traits >
Get number of Active Degrees of Freedon (DOFs). This method computes and returns the number of active degrees of freedom for the bone. This number is related directly to the specified joint type of the bone.
- Returns:
- The number of active degrees of freedom of the bone.
template<typename base_bone_traits >
template<typename bone_type , typename chain_type , typename matrix_range >
Computes the Jacobian matrix corresponding to this bone
bone The bone for which the Jacobian is to be calculated chain The corresponding chain for specified bone. J Upon return this holds the bub-block of the Jacobian corresponding to the specified bone and end-effector of the corresponding chain.
template<typename base_bone_traits >
template<typename bone_type , typename vector_range >
Extract joint limits of a Bone.
- Parameters:
-
| bone | The bone that should be worked on. |
| sub_min | A vector or vector range that upon return holds the minimum joint limits of the specified bone. |
| sub_max | A vector or vector range that upon return holds the maximum joint limits of the specified bone. |
template<typename base_bone_traits >
template<typename bone_type , typename vector_range >
Extract Joint Parameter Values of a Bone.
- Parameters:
-
| bone | The bone that should be worked on. |
| sub_theta | A vector or vector range that upon return holds the joint parameter values of the specified bone. |
template<typename base_bone_traits >
template<typename bone_type , typename vector_range >
Project sub-vector onto joint limits of a Bone.
- Warning:
- Note that the joint parameter values are not extracted from the bone, rather it is assumed that the specified sub-vector contains the current joint paramter values that should be used.
- Parameters:
-
| bone | The bone that should be worked on. |
| sub_theta | A vector or vector range that initially holds the current joint parameter values of the specified bone and which upon return holds the projected values. |
template<typename base_bone_traits >
Get Maximum Joint Limit.
- Parameters:
-
| i | The index of the value for which the limits is wanted. |
- Returns:
- A reference to the corresponding joint limit.
template<typename base_bone_traits >
Get Maximum Joint Limit.
- Parameters:
-
| i | The index of the value for which the limits is wanted. |
- Returns:
- A reference to the corresponding joint limit.
template<typename base_bone_traits >
Get Minimum Joint Limit.
- Parameters:
-
| i | The index of the value for which the limits is wanted. |
- Returns:
- A reference to the corresponding joint limit.
template<typename base_bone_traits >
Get Minimum Joint Limit.
- Parameters:
-
| i | The index of the value for which the limits is wanted. |
- Returns:
- A reference to the corresponding joint limit.
template<typename base_bone_traits >
template<typename bone_type , typename vector_range >
Set Joint Parameter Values. This method reads the joint parameter values from a specified sub-vector. The function copies the values into the local storage in this bone and further it sets the relative transformation of the bone to match the joint parameter values.
It is rather important that the relative transformation of the bone is updated accordingly otherwise other libraries like skinning and animation will stop working correctly when used together with the inverse kinematics library.
- Warning:
- Observe that after having set the joint parameter values of all bones then one should also re-compute the absolute bone transformations if these are needed. The inverse kinematics library will do this by default.
- Parameters:
-
| bone | The bone that should be worked on. |
| sub_theta | A vector or vector range from which the joint parameters should be extracted. |
template<typename base_bone_traits >
Get Joint Parameter Value.
- Parameters:
-
| i | The index of the joint parameter value that is wanted. |
- Returns:
- A reference to the corresponding joint parameter value.
template<typename base_bone_traits >
Get Joint Parameter Value.
- Parameters:
-
| i | The index of the joint paramter value that is wanted. |
- Returns:
- A reference to the corresponding joint parameter value.
template<typename base_bone_traits >
template<typename base_bone_traits >
Get Joint Type.
- Returns:
- A reference to the joint type of this bone.
template<typename base_bone_traits >
template<typename base_bone_traits >
Get Joint Axis.
- Returns:
- A reference to the joint axis. This is used for specifying the motion of slider and revolute joint types. It is un-needed for ball type joints.
Member Data Documentation
template<typename base_bone_traits >
Maximum joint parameter value.
template<typename base_bone_traits >
Minimum joint parameter value.
template<typename base_bone_traits >
template<typename base_bone_traits >
The joint type that this bone is connected to its parent bone with.
template<typename base_bone_traits >
Unit joint axis, given as a constant vector in parent frame.
The documentation for this class was generated from the following file:
- /home/hauberg/Dokumenter/Capture/humim-tracker-0.1/src/OpenTissue/OpenTissue/kinematics/inverse/inverse_bone_traits.h