Blender  V3.3
ublas_types.hpp
Go to the documentation of this file.
1 /* SPDX-License-Identifier: LGPL-2.1-or-later
2  * Copyright 2009 Ruben Smits. */
3 
8 #ifndef UBLAS_TYPES_HPP_
9 #define UBLAS_TYPES_HPP_
10 
11 #include <boost/numeric/ublas/matrix.hpp>
12 #include <boost/numeric/ublas/vector.hpp>
13 #include <boost/numeric/ublas/matrix_proxy.hpp>
14 #include <boost/numeric/ublas/vector_proxy.hpp>
15 #include "kdl/frames.hpp"
16 #include "kdl/tree.hpp"
17 #include "kdl/chain.hpp"
18 #include "kdl/jacobian.hpp"
19 #include "kdl/jntarray.hpp"
20 
21 
22 namespace iTaSC{
23 
24 namespace ublas = boost::numeric::ublas;
25 using KDL::Twist;
26 using KDL::Frame;
27 using KDL::Joint;
28 using KDL::Inertia;
29 using KDL::SegmentMap;
30 using KDL::Tree;
31 using KDL::JntArray;
32 using KDL::Jacobian;
33 using KDL::Segment;
34 using KDL::Rotation;
35 using KDL::Vector;
36 using KDL::Chain;
37 
38 #define u_scalar double
39 #define u_vector ublas::vector<u_scalar>
40 #define u_zero_vector ublas::zero_vector<u_scalar>
41 #define u_matrix ublas::matrix<u_scalar>
42 #define u_matrix6 ublas::matrix<u_scalar,6,6>
43 #define u_identity_matrix ublas::identity_matrix<u_scalar>
44 #define u_scalar_vector ublas::scalar_vector<u_scalar>
45 #define u_zero_matrix ublas::zero_matrix<u_scalar>
46 #define u_vector6 ublas::bounded_vector<u_scalar,6>
47 
48 inline static int changeBase(const u_matrix& J_in, const Frame& T, u_matrix& J_out) {
49 
50  if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
51  return -1;
52  for (unsigned int j = 0; j < J_in.size2(); ++j) {
53  ublas::matrix_column<const u_matrix > Jj_in = column(J_in,j);
54  ublas::matrix_column<u_matrix > Jj_out = column(J_out,j);
55  Twist arg;
56  for(unsigned int i=0;i<6;++i)
57  arg(i)=Jj_in(i);
58  Twist tmp(T*arg);
59  for(unsigned int i=0;i<6;++i)
60  Jj_out(i)=tmp(i);
61  }
62  return 0;
63 }
64 inline static int changeBase(const ublas::matrix_range<u_matrix >& J_in, const Frame& T, ublas::matrix_range<u_matrix >& J_out) {
65 
66  if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
67  return -1;
68  for (unsigned int j = 0; j < J_in.size2(); ++j) {
69  ublas::matrix_column<const ublas::matrix_range<u_matrix > > Jj_in = column(J_in,j);
70  ublas::matrix_column<ublas::matrix_range<u_matrix > > Jj_out = column(J_out,j);
71  Twist arg;
72  for(unsigned int i=0;i<6;++i)
73  arg(i)=Jj_in(i);
74  Twist tmp(T*arg);
75  for(unsigned int i=0;i<6;++i)
76  Jj_out(i)=tmp(i);
77  }
78  return 0;
79 }
80 
81 }
82 #endif /* UBLAS_TYPES_HPP_ */
struct Frame Frame
Definition: frames.hpp:261
This class encapsulates a serial kinematic interconnection structure. It is build out of segments.
Definition: chain.hpp:36
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:526
This class encapsulates a simple joint, that is with one parameterized degree of freedom and with sca...
Definition: joint.hpp:43
represents rotations in 3 dimensional space.
Definition: frames.hpp:299
This class encapsulates a simple segment, that is a "rigid body" (i.e., a frame and an inertia) with...
Definition: segment.hpp:46
This class encapsulates a tree kinematic interconnection structure. It is build out of segments.
Definition: tree.hpp:68
represents both translational and rotational velocities.
Definition: frames.hpp:679
A concrete implementation of a 3 dimensional vector class.
Definition: frames.hpp:143
#define T
std::map< std::string, TreeElement, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, TreeElement > > > SegmentMap
Definition: tree.hpp:35
static int changeBase(Eigen::MatrixBase< Derived > &J, const Frame &T)
Definition: eigen_types.hpp:67
#define u_matrix
Definition: ublas_types.hpp:41