#include <inverse_chain.h>
List of all members.
Detailed Description
template<typename skeleton_type_>
class OpenTissue::kinematics::inverse::Chain< skeleton_type_ >
Chain Class. This class represents a kinematic chain in a skeleton.
A kinematic chain is simply a connected sequence of bones. The first bone in the sequence is named the root-bone and the last bone is named the end-effector.
Observe that the root of a kinematic chain does not need to be the root of the skeleton. However, the root of the chain does need to be the ``inboard'' bone and the end-effector needs to the be the ``outboard'' bone.
By inboard we mean closer to the root of the skeleton and by outboard we mean further away from the skeleton root.
- Template Parameters:
-
| skeleton_type_ | The type of skeleton that this kinematic chain can be defined on. |
Member Typedef Documentation
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
Member Function Documentation
template<typename skeleton_type_ >
Get Bone Iterator.
- Returns:
- A bone iterator to the first bone in the chain.
template<typename skeleton_type_ >
Get End Bone Iterator.
- Returns:
- A bone iterator to the position one past the last bone (i.e. the end-effector) in the chain.
template<typename skeleton_type_ >
Get end-effector Bone.
- Returns:
- A pointer to the end-effector bone or null if the chain is un-initialized.
template<typename skeleton_type_ >
Get Dimension of Goal.
- Returns:
- The dimension of the goal placement. If only positional then the dimension is 3. If both position and orientation is specified then the dimension is 9.
template<typename skeleton_type_ >
Get Root Bone.
A pointer to the root bone of the chain or null if the chain is not initialised.
template<typename skeleton_type_ >
Initialize Chain. This method traverses all the bones inbetween the specified end-effector and root. While traversing the bones they are added to the chain.
- Parameters:
-
| root_ | A pointer to the root bone of the chain. |
| end_effector_ | A pointer to the end-effector bone of the chain. |
template<typename skeleton_type_ >
Get Only Positional Flag.
- Returns:
- A reference to a boolean flag. If set to true then the chain goal is only positional and otherwise both positional and orientation.
template<typename skeleton_type_ >
template<typename skeleton_type_ >
Comparison Operator.
- Parameters:
-
| chain | Another chain to compare with. |
- Returns:
- If the other chain have the same root and end-effector then we define the two chains to be the same.
template<typename skeleton_type_ >
Get global transformation
- Returns:
- A reference to the global translation of the end effector i.e in WCS
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
Get Local transformation
- Returns:
- A reference to the local translation of the end effector
template<typename skeleton_type_ >
Get Reverse Bone Iterator.
- Returns:
- A reverse bone iterator to the last bone in the chain (ie. the end-effector).
template<typename skeleton_type_ >
Get Reverse End Bone Iterator.
- Returns:
- A reverse bone iterator to the position just prior to the first bone in the chain (i.e the root).
template<typename skeleton_type_ >
Set Partial Goal Weight.
- Parameters:
-
| value | A non-negative goal weight. Large values means that more importance should be applied to reach the corresponding goal. |
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
Get Partial Goal Weight.
- Returns:
- The current goal weight.
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
Get global transformation
- Returns:
- A reference to the global xaxis of the end effector i.e in WCS
template<typename skeleton_type_ >
template<typename skeleton_type_ >
template<typename skeleton_type_ >
Get Local transformation
- Returns:
- A reference to the local x axis of the end effector
template<typename skeleton_type_ >
Get global transformation
- Returns:
- A reference to the global yaxis of the end effector i.e in WCS
template<typename skeleton_type_ >
template<typename skeleton_type_ >
Get Local transformation
- Returns:
- A reference to the local y axis of the end effector
template<typename skeleton_type_ >
Member Data Documentation
template<typename skeleton_type_ >
All the bones in the chain, stored sequentially from root to end-effector.
template<typename skeleton_type_ >
Boolean flag indicating whether this chain goal is purely positional or if it includes orientation. Default is true.
template<typename skeleton_type_ >
In global world (root) coordinates.
template<typename skeleton_type_ >
In local end-effector coordinates.
template<typename skeleton_type_ >
The weighting of p goal. Default value is one.
template<typename skeleton_type_ >
The weighting of x goal. Default value is one.
template<typename skeleton_type_ >
The weighting of y goal. Default value is one.
template<typename skeleton_type_ >
In global world (root) coordinates.
template<typename skeleton_type_ >
In local end-effector coordinates.
template<typename skeleton_type_ >
In global world (root) coordinates.
template<typename skeleton_type_ >
In local end-effector coordinates.
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_chain.h