/* SPDX-License-Identifier: LGPL-2.1-or-later * Copyright 2009 Ruben Smits. */ /** \file * \ingroup intern_itasc */ #ifndef UBLAS_TYPES_HPP_ #define UBLAS_TYPES_HPP_ #include #include #include #include #include "kdl/frames.hpp" #include "kdl/tree.hpp" #include "kdl/chain.hpp" #include "kdl/jacobian.hpp" #include "kdl/jntarray.hpp" namespace iTaSC{ namespace ublas = boost::numeric::ublas; using KDL::Twist; using KDL::Frame; using KDL::Joint; using KDL::Inertia; using KDL::SegmentMap; using KDL::Tree; using KDL::JntArray; using KDL::Jacobian; using KDL::Segment; using KDL::Rotation; using KDL::Vector; using KDL::Chain; #define u_scalar double #define u_vector ublas::vector #define u_zero_vector ublas::zero_vector #define u_matrix ublas::matrix #define u_matrix6 ublas::matrix #define u_identity_matrix ublas::identity_matrix #define u_scalar_vector ublas::scalar_vector #define u_zero_matrix ublas::zero_matrix #define u_vector6 ublas::bounded_vector inline static int changeBase(const u_matrix& J_in, const Frame& T, u_matrix& J_out) { if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2()) return -1; for (unsigned int j = 0; j < J_in.size2(); ++j) { ublas::matrix_column Jj_in = column(J_in,j); ublas::matrix_column Jj_out = column(J_out,j); Twist arg; for(unsigned int i=0;i<6;++i) arg(i)=Jj_in(i); Twist tmp(T*arg); for(unsigned int i=0;i<6;++i) Jj_out(i)=tmp(i); } return 0; } inline static int changeBase(const ublas::matrix_range& J_in, const Frame& T, ublas::matrix_range& J_out) { if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2()) return -1; for (unsigned int j = 0; j < J_in.size2(); ++j) { ublas::matrix_column > Jj_in = column(J_in,j); ublas::matrix_column > Jj_out = column(J_out,j); Twist arg; for(unsigned int i=0;i<6;++i) arg(i)=Jj_in(i); Twist tmp(T*arg); for(unsigned int i=0;i<6;++i) Jj_out(i)=tmp(i); } return 0; } } #endif /* UBLAS_TYPES_HPP_ */