9#ifndef UBLAS_TYPES_HPP_
10#define UBLAS_TYPES_HPP_
12#include <boost/numeric/ublas/matrix.hpp>
13#include <boost/numeric/ublas/vector.hpp>
14#include <boost/numeric/ublas/matrix_proxy.hpp>
15#include <boost/numeric/ublas/vector_proxy.hpp>
25namespace ublas = boost::numeric::ublas;
39#define u_scalar double
40#define u_vector ublas::vector<u_scalar>
41#define u_zero_vector ublas::zero_vector<u_scalar>
42#define u_matrix ublas::matrix<u_scalar>
43#define u_matrix6 ublas::matrix<u_scalar,6,6>
44#define u_identity_matrix ublas::identity_matrix<u_scalar>
45#define u_scalar_vector ublas::scalar_vector<u_scalar>
46#define u_zero_matrix ublas::zero_matrix<u_scalar>
47#define u_vector6 ublas::bounded_vector<u_scalar,6>
51 if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
53 for (
unsigned int j = 0; j < J_in.size2(); ++j) {
54 ublas::matrix_column<const u_matrix > Jj_in = column(J_in,j);
55 ublas::matrix_column<u_matrix > Jj_out = column(J_out,j);
57 for(
unsigned int i=0;i<6;++i)
60 for(
unsigned int i=0;i<6;++i)
65inline static int changeBase(
const ublas::matrix_range<u_matrix >& J_in,
const Frame& T, ublas::matrix_range<u_matrix >& J_out) {
67 if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
69 for (
unsigned int j = 0; j < J_in.size2(); ++j) {
70 ublas::matrix_column<const ublas::matrix_range<u_matrix > > Jj_in = column(J_in,j);
71 ublas::matrix_column<ublas::matrix_range<u_matrix > > Jj_out = column(J_out,j);
73 for(
unsigned int i=0;i<6;++i)
76 for(
unsigned int i=0;i<6;++i)
This class encapsulates a serial kinematic interconnection structure. It is build out of segments.
represents a frame transformation in 3D space (rotation + translation)
This class encapsulates a simple joint, that is with one parameterized degree of freedom and with sca...
represents rotations in 3 dimensional space.
This class encapsulates a simple segment, that is a "rigid body" (i.e., a frame and an inertia) with ...
This class encapsulates a tree kinematic interconnection structure. It is build out of segments.
represents both translational and rotational velocities.
A concrete implementation of a 3 dimensional vector class.
std::map< std::string, TreeElement, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, TreeElement > > > SegmentMap
static int changeBase(Eigen::MatrixBase< Derived > &J, const Frame &T)