Go to the documentation of this file.00001 #ifndef OPENTISSUE_KINEMATICS_INVERSE_INVERSE_COMPUTE_JOINT_LIMITS_PROJECTION_H
00002 #define OPENTISSUE_KINEMATICS_INVERSE_INVERSE_COMPUTE_JOINT_LIMITS_PROJECTION_H
00003
00004
00005
00006
00007
00008
00009
00010 #include <OpenTissue/configuration.h>
00011
00012 #include <OpenTissue/core/math/big/big_types.h>
00013
00014 #include <cassert>
00015
00016 namespace OpenTissue
00017 {
00018 namespace kinematics
00019 {
00020 namespace inverse
00021 {
00022
00038 template< typename skeleton_type>
00039 inline void compute_joint_limits_projection(
00040 skeleton_type const & skeleton
00041 , ublas::vector<typename skeleton_type::bone_traits::real_type> & theta
00042 )
00043 {
00044 using ublas::subrange;
00045
00046 typedef typename skeleton_type::bone_traits bone_traits;
00047 typedef typename bone_traits::real_type real_type;
00048 typedef ublas::vector<real_type> vector_type;
00049 typedef ublas::vector_range<vector_type> vector_range;
00050
00051 typename skeleton_type::const_bone_iterator bone = skeleton.begin();
00052 typename skeleton_type::const_bone_iterator end = skeleton.end();
00053
00054 size_t i = 0u;
00055 size_t dof = 0u;
00056
00057 for(;bone!=end;++bone)
00058 {
00059 dof = bone->active_dofs();
00060
00061 vector_range sub_theta = subrange(theta,i,i+dof);
00062
00063 bone_traits::joint_limit_projection( *bone , sub_theta );
00064
00065 i += dof;
00066 }
00067
00068 assert( theta.size() == i || !"compute_joint_limits_projection(): incompatible dimensions");
00069 }
00070
00071 }
00072 }
00073 }
00074
00075
00076 #endif