Blender V2.61 - r43446

ublas_types.hpp

Go to the documentation of this file.
00001 /*
00002  * ublas_types.hpp
00003  *
00004  *  Created on: Jan 5, 2009
00005  *      Author: rubensmits
00006  */
00007 
00008 #ifndef UBLAS_TYPES_HPP_
00009 #define UBLAS_TYPES_HPP_
00010 
00011 #include <boost/numeric/ublas/matrix.hpp>
00012 #include <boost/numeric/ublas/vector.hpp>
00013 #include <boost/numeric/ublas/matrix_proxy.hpp>
00014 #include <boost/numeric/ublas/vector_proxy.hpp>
00015 #include "kdl/frames.hpp"
00016 #include "kdl/tree.hpp"
00017 #include "kdl/chain.hpp"
00018 #include "kdl/jacobian.hpp"
00019 #include "kdl/jntarray.hpp"
00020 
00021 
00022 namespace iTaSC{
00023 
00024 namespace ublas = boost::numeric::ublas;
00025 using KDL::Twist;
00026 using KDL::Frame;
00027 using KDL::Joint;
00028 using KDL::Inertia;
00029 using KDL::SegmentMap;
00030 using KDL::Tree;
00031 using KDL::JntArray;
00032 using KDL::Jacobian;
00033 using KDL::Segment;
00034 using KDL::Rotation;
00035 using KDL::Vector;
00036 using KDL::Chain;
00037 
00038 #define u_scalar double
00039 #define u_vector ublas::vector<u_scalar>
00040 #define u_zero_vector ublas::zero_vector<u_scalar>
00041 #define u_matrix ublas::matrix<u_scalar>
00042 #define u_matrix6 ublas::matrix<u_scalar,6,6>
00043 #define u_identity_matrix ublas::identity_matrix<u_scalar>
00044 #define u_scalar_vector ublas::scalar_vector<u_scalar>
00045 #define u_zero_matrix ublas::zero_matrix<u_scalar>
00046 #define u_vector6 ublas::bounded_vector<u_scalar,6>
00047 
00048 inline static int changeBase(const u_matrix& J_in, const Frame& T, u_matrix& J_out) {
00049 
00050     if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
00051         return -1;
00052     for (unsigned int j = 0; j < J_in.size2(); ++j) {
00053         ublas::matrix_column<const u_matrix > Jj_in = column(J_in,j);
00054         ublas::matrix_column<u_matrix > Jj_out = column(J_out,j);
00055         Twist arg;
00056         for(unsigned int i=0;i<6;++i)
00057             arg(i)=Jj_in(i);
00058         Twist tmp(T*arg);
00059         for(unsigned int i=0;i<6;++i)
00060                     Jj_out(i)=tmp(i);
00061     }
00062     return 0;
00063 }
00064 inline static int changeBase(const ublas::matrix_range<u_matrix >& J_in, const Frame& T, ublas::matrix_range<u_matrix >& J_out) {
00065 
00066     if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
00067         return -1;
00068     for (unsigned int j = 0; j < J_in.size2(); ++j) {
00069         ublas::matrix_column<const ublas::matrix_range<u_matrix > > Jj_in = column(J_in,j);
00070         ublas::matrix_column<ublas::matrix_range<u_matrix > > Jj_out = column(J_out,j);
00071         Twist arg;
00072         for(unsigned int i=0;i<6;++i)
00073             arg(i)=Jj_in(i);
00074         Twist tmp(T*arg);
00075         for(unsigned int i=0;i<6;++i)
00076                     Jj_out(i)=tmp(i);
00077     }
00078     return 0;
00079 }
00080 
00081 }
00082 #endif /* UBLAS_TYPES_HPP_ */