Go to the documentation of this file.00001 #ifndef OPENTISSUE_KINEMATICS_INVERSE_INVERSE_MAKE_SOLVER_H
00002 #define OPENTISSUE_KINEMATICS_INVERSE_INVERSE_MAKE_SOLVER_H
00003
00004
00005
00006
00007
00008
00009
00010 #include <OpenTissue/configuration.h>
00011
00012 #include <OpenTissue/kinematics/inverse/inverse_nonlinear_solver.h>
00013
00014 namespace OpenTissue
00015 {
00016 namespace kinematics
00017 {
00018 namespace inverse
00019 {
00020
00050 template<typename skeleton_type>
00051 inline NonlinearSolver<skeleton_type> make_solver( skeleton_type const & skeleton )
00052 {
00053 typedef NonlinearSolver<skeleton_type> solver_type;
00054 typedef typename solver_type::chain_type chain_type;
00055 typedef typename skeleton_type::const_bone_iterator const_bone_iterator;
00056 typedef typename skeleton_type::bone_type bone_type;
00057
00058 solver_type solver;
00059
00060 solver.init( skeleton );
00061 const_bone_iterator bone = skeleton.begin();
00062 const_bone_iterator end = skeleton.end();
00063 for( ; bone!=end; ++bone)
00064 {
00065 if(!bone->is_leaf())
00066 continue;
00067
00068 chain_type chain;
00069 chain.init( skeleton.root(), &(*bone) );
00070
00071 solver.add_chain( chain );
00072 }
00073 return solver;
00074 }
00075
00076 }
00077 }
00078 }
00079
00080
00081 #endif