Namespaces | Classes | Functions

OpenTissue::kinematics::inverse Namespace Reference

Namespaces

namespace  detail

Classes

class  BoneTraits
class  Chain

Functions

template<typename solver_type >
solver_type::chain_iterator add_chain (solver_type &solver, typename solver_type::skeleton_type::bone_type const &root_, typename solver_type::skeleton_type::bone_type const &end_effector)
template<typename bone_type >
void synchronize_bone (bone_type &bone)
template<typename chain_iterator , typename bone_iterator , typename matrix_type >
void compute_jacobian (chain_iterator const &chain_begin, chain_iterator const &chain_end, bone_iterator const &bone_begin, bone_iterator const &bone_end, matrix_type &J)
template<typename skeleton_type >
void compute_joint_limits_projection (skeleton_type const &skeleton, ublas::vector< typename skeleton_type::bone_traits::real_type > &theta)
template<typename chain_iterator , typename T >
void compute_weighted_difference (chain_iterator const &begin, chain_iterator const &end, ublas::vector< T > &delta)
template<typename sample_iterator , typename bone_type >
void estimate_joint_type (sample_iterator const &begin, sample_iterator const &end, bone_type &bone)
template<typename blend_scheduler_type , typename skeleton_type >
void estimate_joints (blend_scheduler_type &scheduler, skeleton_type &skeleton)
template<typename skeleton_type >
void get_joint_limits (skeleton_type const &skeleton, ublas::vector< typename skeleton_type::bone_traits::real_type > &min_theta, ublas::vector< typename skeleton_type::bone_traits::real_type > &max_theta)
template<typename skeleton_type >
void get_joint_parameters (skeleton_type const &skeleton, ublas::vector< typename skeleton_type::bone_traits::real_type > &theta)
template<typename skeleton_type >
NonlinearSolver< skeleton_typemake_solver (skeleton_type const &skeleton)
template<typename skeleton_type >
void set_default_joint_settings (skeleton_type &skeleton)
template<typename skeleton_type >
void set_joint_parameters (skeleton_type &skeleton, ublas::vector< typename skeleton_type::bone_traits::real_type > const &theta)
template<typename blend_scheduler_type , typename skeleton_type >
std::vector< std::vector
< typename
skeleton_type::bone_traits::transform_type > > 
sample_motion (blend_scheduler_type &scheduler, skeleton_type &skeleton)
template<typename blend_scheduler_type , typename skeleton_type >
void sample_motion_bones (blend_scheduler_type &scheduler, skeleton_type &skeleton, std::vector< std::vector< typename skeleton_type::bone_type > > &transforms)
template<typename pose_iterator >
void write_sampled_transforms (std::string const &prefix, std::string const &matlab_filename, std::string const &latex_filename, pose_iterator begin, pose_iterator end)
template<typename solver_type >
bool xml_read (std::string const &filename, solver_type &solver, bool const &read_skeleton=true)
template<typename solver_type >
bool xml_write (std::string const &filename, solver_type const &solver, bool const &write_skeleton=true)

Function Documentation

template<typename solver_type >
solver_type::chain_iterator OpenTissue::kinematics::inverse::add_chain ( solver_type solver,
typename solver_type::skeleton_type::bone_type const &  root_,
typename solver_type::skeleton_type::bone_type const &  end_effector 
) [inline]

Add Chain to Inverse Kinematics Solver. This convenience function will create a new chain and add it to the specified solver. Obsreve that a chain is a connected sequence of bones. The root of the chain does not have to be the root bone of the skeleton. The end-bone of the chain sequence is called the end-effector of the chain.

Parameters:
solver The solver that the new chain should be added to.
root A reference to the root of the new chain
end_effector The end-effector of the new chain.
Returns:
An iterator to the newly added chain.
template<typename chain_iterator , typename bone_iterator , typename matrix_type >
void OpenTissue::kinematics::inverse::compute_jacobian ( chain_iterator const &  chain_begin,
chain_iterator const &  chain_end,
bone_iterator const &  bone_begin,
bone_iterator const &  bone_end,
matrix_type J 
) [inline]

Compute Jacobian For the Kinematic Chains. This function will first determine the size of the Jacobian matrix and the non-zero block pattern layout of the Jacobian matrix. Following this the function will fill in values into the Jacobian matrix.

It is implicitly assumed that all the kinematics chains are comming from the same skeleton.

Parameters:
chain_begin An iterator to the first chain.
chain_end An iterator to one past the last chain.
bone_begin An iterator to the first bone.
bone_end An iterator to one past the last bone.
J Upon return this argument will hold the Jacobian corresponding to all the chains in the specified sequence.

< Entry i holds the starting row index of the i'th chain.

< The i'th entry holds the starting column index of the i'th bone

< The number of rows in the Jacobian

< The number of columns in the Jacobian

< The i'th entry holds the number of degrees of freedom of the i'th bone

template<typename skeleton_type >
void OpenTissue::kinematics::inverse::compute_joint_limits_projection ( skeleton_type const &  skeleton,
ublas::vector< typename skeleton_type::bone_traits::real_type > &  theta 
) [inline]

Compute projectino onto upper and lower joint limits. This function will iterate over all the bones in the specified skeleton and extract the joint limits for each bone and project the corresponding sub-block of the agglomerated joint parameter vector onto these limits.

Parameters:
skeleton The skeleton from which joint parameter values should be extracted.
theta Upon invokation this argument holds the current value of the agglomerated joint parameter values and Upon return it holds the projected values.
template<typename chain_iterator , typename T >
void OpenTissue::kinematics::inverse::compute_weighted_difference ( chain_iterator const &  begin,
chain_iterator const &  end,
ublas::vector< T > &  delta 
) [inline]

Compute Weighted Goal End-effector Difference Vector. This function computes the vector given by

\[ W (g-F(\Theta)) \]

Parameters:
begin An iterator to the first chain.
end An iterator to one past the last chain.
delta upon return this holds the weighted difference between all end effectors and all goals
template<typename sample_iterator , typename bone_type >
void OpenTissue::kinematics::inverse::estimate_joint_type ( sample_iterator const &  begin,
sample_iterator const &  end,
bone_type bone 
) [inline]

Estimate Joint Type and Joint Paramters. This function tries to analyse motion samples of the relative motion of a skeleton bone. The function first tries to analyse whether a bone is a hinge or ball type joint. Hereafter the function tries to find a minimal boxed joint limit domain for the specifically chosen joint type.

Parameters:
begin An iterator to the position of the first motion sample.
end An iterator to one past the last motion sample.
bone The bone corresponding to the joint that should be estimated.

< Threshold value used to determine too small eigen values!

< Mean point

< Covariance Matrix

< Column vectors are eigen vectors.

< Vector of eigen values

template<typename blend_scheduler_type , typename skeleton_type >
void OpenTissue::kinematics::inverse::estimate_joints ( blend_scheduler_type &  scheduler,
skeleton_type skeleton 
) [inline]

Estimate Joint types and Joint Settings. This function tries to estimate the joints of a skeleton by looking at motion samples.

The intention is that this function can be used to provide an end-user with a pre-set of joint types and joint limits, which can be further fine-tuned by hand.

Parameters:
scheduler A motion blend scheduler, which is used for sampling the motion.
skeleton The skeleton for which we which to estimate the joints for.

< Number of samples

template<typename skeleton_type >
void OpenTissue::kinematics::inverse::get_joint_limits ( skeleton_type const &  skeleton,
ublas::vector< typename skeleton_type::bone_traits::real_type > &  min_theta,
ublas::vector< typename skeleton_type::bone_traits::real_type > &  max_theta 
) [inline]

Get upper and lower limits of the joint parameters. This function will iterate over all the bones in the specified skeleton and extract the joint limits for each bone and copy these into agglomerated vectors.

Parameters:
skeleton The skeleton from which joint limits should be extracted.
min_theta Upon return this argument holds the agglomerated vector of minimum joint limits.
max_theta Upon return this argument holds the agglomerated vector of maximum joint limits.
template<typename skeleton_type >
void OpenTissue::kinematics::inverse::get_joint_parameters ( skeleton_type const &  skeleton,
ublas::vector< typename skeleton_type::bone_traits::real_type > &  theta 
) [inline]

Get Joint Parameter Values. This function will iterate over all the bones in the specified skeleton and extract the joint parameters for each bone and copy these into an agglomerated vector.

Parameters:
skeleton The skeleton from which joint parameter values should be extracted.
theta Upon return this argument holds the agglomerated vector of joint parameter values.
template<typename skeleton_type >
NonlinearSolver<skeleton_type> OpenTissue::kinematics::inverse::make_solver ( skeleton_type const &  skeleton  )  [inline]

Make Inverse Kinematics Nonlinear Solver. This convenience function assist one in creating and initializing a non-linear inverse kinemtics solver. The function will create an inverse kinmatics solver for a specified given skeleton by writting

This convenience function will tie the skeleton to the solver and by default create inverse kinematic chains. The skeleton three structure is used as the basis for the chain creation. Every leaf bone will correspond to one end-effector in one chain and all chains will share the same root bone. Afterwards one can iterate through the created inverse kinematic chains.

 solver_type::chain_iterator chain = solver.chain_begin();
 solver_type::chain_iterator end   = solver.chain_end();
 for(;chain!=end;++chain)
 {
    ... do something with chain ...
 }

One can store the chain iterators for later manipulation. During a simulation loop one would typical use the chain iterators to set up desired goal placments for the end-effector of a chain.

Parameters:
skeleton The skeleton that should be used to initialize the new solver.
Returns:
The new solver.
template<typename blend_scheduler_type , typename skeleton_type >
std::vector< std::vector<typename skeleton_type::bone_traits::transform_type> > OpenTissue::kinematics::inverse::sample_motion ( blend_scheduler_type &  scheduler,
skeleton_type skeleton 
) [inline]

< Number of samples

template<typename blend_scheduler_type , typename skeleton_type >
void OpenTissue::kinematics::inverse::sample_motion_bones ( blend_scheduler_type &  scheduler,
skeleton_type skeleton,
std::vector< std::vector< typename skeleton_type::bone_type > > &  transforms 
) [inline]

this version collects the entire output with all the goodies in it it is done in the bones since these have all the interface to get to the juicy parts inside

< Number of samples

template<typename skeleton_type >
void OpenTissue::kinematics::inverse::set_default_joint_settings ( skeleton_type skeleton  )  [inline]

Set Default Joint Paramter values of a given Skeleton. This convenience function tries to extract meningful joint parameter settings from a given skeleton from the current relative bone transformations and joint types.

The function is intended to aid end-users in faster and easier rigging of characters. The idea is that the function tries to come up with some good guess for the joint parameter values and the joint limits. Hereafter an end-user should fine tune and adjust the settings.

Warning:
Make sure that the relative bone transforms have been set prior to invoking this method. This could for instance be done by invoking the skelton.set_bind_pose() method. Also make sure to set the joint types of each bone. If not the default joint type will be assumed.
Parameters:
skeleton The skeleton that the function should work on.
template<typename skeleton_type >
void OpenTissue::kinematics::inverse::set_joint_parameters ( skeleton_type skeleton,
ublas::vector< typename skeleton_type::bone_traits::real_type > const &  theta 
)

Set Joint Parameter Values. This function takes an agglomerated vector of joint parameters and transfer its values onto the bones/joints of a skeleton. During the process the relative transform of the bones in the skeleton are updated and upon completion before returning the absolute transformations of the bones are computed.

Parameters:
skeleton The skeleton where joint parameters should be set.
theta Agglomerated vector of joint parameter values.
template<typename bone_type >
void OpenTissue::kinematics::inverse::synchronize_bone ( bone_type bone  )  [inline]

Synchronize Bone. Synchronize makes sure the theta vector of a bone is equivalent to the actual pose of the bone. It uses the absolute pose of the bone for this so it is important to make sure this is updated e.g. by running compute_pose() on the skeleton. It is useful if one has performed forward kinematics on an inverse kinematics skeleton The computations are the same as in the function set default joint parameters except this function uses the absolute pose while the other one uses bind_pose.

Parameters:
bone The bone which should be synchronized
template<typename pose_iterator >
void OpenTissue::kinematics::inverse::write_sampled_transforms ( std::string const &  prefix,
std::string const &  matlab_filename,
std::string const &  latex_filename,
pose_iterator  begin,
pose_iterator  end 
) [inline]

Write Sampled Data Matlab writer for the sampled data of one bone.

This is a utility function that is to be used in conjunction with the sample_motion function. it writes the sampled data to a matlab script. the transforms are all coordinate systems so we will use the interface from these.

Parameters:
prefix A string value that is used to prefix all matlab figures. This is useful to make sure that the generated figures in the end all have unique names.
matlab_filename The path and name of the resulting matlab script. Running this script from matlab will produce a set of figures. Also all figures are automatically exported as both eps and png files.
latex_filename The path and name of the resulting latex file. Upon return this file will contain latex code for some of the statistics.
begin An iterator to the position of the first Output class.
end An iterator to the position one past the last Output class.
template<typename solver_type >
bool OpenTissue::kinematics::inverse::xml_read ( std::string const &  filename,
solver_type solver,
bool const &  read_skeleton = true 
)

Read Solver from XML file.

Parameters:
filename The filename of the XML file that should be read.
solver Upon return this argument holds the solver data that has been read from the XML file.
read_skeleton Boolean flag indicating whether the skeleton data should be read as well.
Returns:
If the read operation was succesfully then the return value is true otherwise it is false.
template<typename solver_type >
bool OpenTissue::kinematics::inverse::xml_write ( std::string const &  filename,
solver_type const &  solver,
bool const &  write_skeleton = true 
)

Write Solver to XML file.

Parameters:
filename The filename of the XML file that should be written.
solver This argument holds the solver data that should be written to the XML file.
write_skeleton Boolean flag indicating whether skeleton info should be written as well.
Returns:
If the write operation was succesfully then the return value is true otherwise it is false.