Public Types | Public Member Functions | Protected Types | Protected Attributes

OpenTissue::kinematics::inverse::Chain< skeleton_type_ > Class Template Reference

#include <inverse_chain.h>

List of all members.

Public Types

typedef skeleton_type_ skeleton_type
typedef skeleton_type::math_types math_types
typedef skeleton_type::bone_type bone_type
typedef skeleton_type::bone_traits bone_traits
typedef math_types::real_type real_type
typedef math_types::vector3_type vector3_type
typedef
boost::indirect_iterator
< bone_ptr_iterator
bone_iterator
typedef
boost::indirect_iterator
< reverse_bone_ptr_iterator
reverse_bone_iterator

Public Member Functions

bool & only_position ()
bool const & only_position () const
vector3_type const & p_local () const
vector3_typep_local ()
vector3_type const & x_local () const
vector3_typex_local ()
vector3_type const & y_local () const
vector3_typey_local ()
vector3_type const & p_global () const
vector3_typep_global ()
vector3_type const & x_global () const
vector3_typex_global ()
vector3_type const & y_global () const
vector3_typey_global ()
real_type const & weight_p () const
real_type const & weight_x () const
real_type const & weight_y () const
void set_weight_p (real_type const &value)
void set_weight_x (real_type const &value)
void set_weight_y (real_type const &value)
bool operator== (Chain const &chain)
void init (bone_type const *root_, bone_type const *end_effector_)
bone_iterator bone_begin ()
bone_iterator bone_end ()
reverse_bone_iterator rbone_begin ()
reverse_bone_iterator rbone_end ()
bone_type *const get_root () const
bone_type *const get_end_effector () const
size_t get_goal_dimension () const

Protected Types

typedef math_types::value_traits value_traits
typedef std::list< bone_type * > bone_container
typedef bone_container::iterator bone_ptr_iterator
typedef
bone_container::reverse_iterator 
reverse_bone_ptr_iterator

Protected Attributes

bone_container m_bones
 All the bones in the chain, stored sequentially from root to end-effector.
bool m_only_position
 Boolean flag indicating whether this chain goal is purely positional or if it includes orientation. Default is true.
vector3_type m_p_local
 In local end-effector coordinates.
vector3_type m_x_local
 In local end-effector coordinates.
vector3_type m_y_local
 In local end-effector coordinates.
vector3_type m_p_global
 In global world (root) coordinates.
vector3_type m_x_global
 In global world (root) coordinates.
vector3_type m_y_global
 In global world (root) coordinates.
real_type m_weight_p
 The weighting of p goal. Default value is one.
real_type m_weight_x
 The weighting of x goal. Default value is one.
real_type m_weight_y
 The weighting of y goal. Default value is one.

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_ >
typedef std::list<bone_type*> OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::bone_container [protected]
template<typename skeleton_type_ >
typedef boost::indirect_iterator<bone_ptr_iterator> OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::bone_iterator
template<typename skeleton_type_ >
typedef bone_container::iterator OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::bone_ptr_iterator [protected]
template<typename skeleton_type_ >
typedef skeleton_type::bone_traits OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::bone_traits
template<typename skeleton_type_ >
typedef skeleton_type::bone_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::bone_type
template<typename skeleton_type_ >
typedef skeleton_type::math_types OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::math_types
template<typename skeleton_type_ >
typedef math_types::real_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::real_type
template<typename skeleton_type_ >
typedef boost::indirect_iterator<reverse_bone_ptr_iterator> OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::reverse_bone_iterator
template<typename skeleton_type_ >
typedef bone_container::reverse_iterator OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::reverse_bone_ptr_iterator [protected]
template<typename skeleton_type_ >
typedef skeleton_type_ OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::skeleton_type
template<typename skeleton_type_ >
typedef math_types::value_traits OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::value_traits [protected]
template<typename skeleton_type_ >
typedef math_types::vector3_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::vector3_type

Member Function Documentation

template<typename skeleton_type_ >
bone_iterator OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::bone_begin (  )  [inline]

Get Bone Iterator.

Returns:
A bone iterator to the first bone in the chain.
template<typename skeleton_type_ >
bone_iterator OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::bone_end (  )  [inline]

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_ >
bone_type* const OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::get_end_effector (  )  const [inline]

Get end-effector Bone.

Returns:
A pointer to the end-effector bone or null if the chain is un-initialized.
template<typename skeleton_type_ >
size_t OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::get_goal_dimension (  )  const [inline]

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_ >
bone_type* const OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::get_root (  )  const [inline]

Get Root Bone.

A pointer to the root bone of the chain or null if the chain is not initialised.

template<typename skeleton_type_ >
void OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::init ( bone_type const *  root_,
bone_type const *  end_effector_ 
) [inline]

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_ >
bool& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::only_position (  )  [inline]

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_ >
bool const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::only_position (  )  const [inline]
template<typename skeleton_type_ >
bool OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::operator== ( Chain< skeleton_type_ > const &  chain  )  [inline]

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_ >
vector3_type const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::p_global (  )  const [inline]

Get global transformation

Returns:
A reference to the global translation of the end effector i.e in WCS
template<typename skeleton_type_ >
vector3_type& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::p_global (  )  [inline]
template<typename skeleton_type_ >
vector3_type& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::p_local (  )  [inline]
template<typename skeleton_type_ >
vector3_type const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::p_local (  )  const [inline]

Get Local transformation

Returns:
A reference to the local translation of the end effector
template<typename skeleton_type_ >
reverse_bone_iterator OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::rbone_begin (  )  [inline]

Get Reverse Bone Iterator.

Returns:
A reverse bone iterator to the last bone in the chain (ie. the end-effector).
template<typename skeleton_type_ >
reverse_bone_iterator OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::rbone_end (  )  [inline]

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_ >
void OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::set_weight_p ( real_type const &  value  )  [inline]

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_ >
void OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::set_weight_x ( real_type const &  value  )  [inline]
template<typename skeleton_type_ >
void OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::set_weight_y ( real_type const &  value  )  [inline]
template<typename skeleton_type_ >
real_type const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::weight_p (  )  const [inline]

Get Partial Goal Weight.

Returns:
The current goal weight.
template<typename skeleton_type_ >
real_type const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::weight_x (  )  const [inline]
template<typename skeleton_type_ >
real_type const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::weight_y (  )  const [inline]
template<typename skeleton_type_ >
vector3_type const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::x_global (  )  const [inline]

Get global transformation

Returns:
A reference to the global xaxis of the end effector i.e in WCS
template<typename skeleton_type_ >
vector3_type& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::x_global (  )  [inline]
template<typename skeleton_type_ >
vector3_type& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::x_local (  )  [inline]
template<typename skeleton_type_ >
vector3_type const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::x_local (  )  const [inline]

Get Local transformation

Returns:
A reference to the local x axis of the end effector
template<typename skeleton_type_ >
vector3_type const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::y_global (  )  const [inline]

Get global transformation

Returns:
A reference to the global yaxis of the end effector i.e in WCS
template<typename skeleton_type_ >
vector3_type& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::y_global (  )  [inline]
template<typename skeleton_type_ >
vector3_type const& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::y_local (  )  const [inline]

Get Local transformation

Returns:
A reference to the local y axis of the end effector
template<typename skeleton_type_ >
vector3_type& OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::y_local (  )  [inline]

Member Data Documentation

template<typename skeleton_type_ >
bone_container OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_bones [protected]

All the bones in the chain, stored sequentially from root to end-effector.

template<typename skeleton_type_ >
bool OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_only_position [protected]

Boolean flag indicating whether this chain goal is purely positional or if it includes orientation. Default is true.

template<typename skeleton_type_ >
vector3_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_p_global [protected]

In global world (root) coordinates.

template<typename skeleton_type_ >
vector3_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_p_local [protected]

In local end-effector coordinates.

template<typename skeleton_type_ >
real_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_weight_p [protected]

The weighting of p goal. Default value is one.

template<typename skeleton_type_ >
real_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_weight_x [protected]

The weighting of x goal. Default value is one.

template<typename skeleton_type_ >
real_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_weight_y [protected]

The weighting of y goal. Default value is one.

template<typename skeleton_type_ >
vector3_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_x_global [protected]

In global world (root) coordinates.

template<typename skeleton_type_ >
vector3_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_x_local [protected]

In local end-effector coordinates.

template<typename skeleton_type_ >
vector3_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_y_global [protected]

In global world (root) coordinates.

template<typename skeleton_type_ >
vector3_type OpenTissue::kinematics::inverse::Chain< skeleton_type_ >::m_y_local [protected]

In local end-effector coordinates.


The documentation for this class was generated from the following file: