Blender V4.3
ublas_types.hpp
Go to the documentation of this file.
1/* SPDX-FileCopyrightText: 2009 Ruben Smits
2 *
3 * SPDX-License-Identifier: LGPL-2.1-or-later */
4
9#ifndef UBLAS_TYPES_HPP_
10#define UBLAS_TYPES_HPP_
11
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>
16#include "kdl/frames.hpp"
17#include "kdl/tree.hpp"
18#include "kdl/chain.hpp"
19#include "kdl/jacobian.hpp"
20#include "kdl/jntarray.hpp"
21
22
23namespace iTaSC{
24
25namespace ublas = boost::numeric::ublas;
26using KDL::Twist;
27using KDL::Frame;
28using KDL::Joint;
29using KDL::Inertia;
30using KDL::SegmentMap;
31using KDL::Tree;
32using KDL::JntArray;
33using KDL::Jacobian;
34using KDL::Segment;
35using KDL::Rotation;
36using KDL::Vector;
37using KDL::Chain;
38
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>
48
49inline static int changeBase(const u_matrix& J_in, const Frame& T, u_matrix& J_out) {
50
51 if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
52 return -1;
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);
56 Twist arg;
57 for(unsigned int i=0;i<6;++i)
58 arg(i)=Jj_in(i);
59 Twist tmp(T*arg);
60 for(unsigned int i=0;i<6;++i)
61 Jj_out(i)=tmp(i);
62 }
63 return 0;
64}
65inline static int changeBase(const ublas::matrix_range<u_matrix >& J_in, const Frame& T, ublas::matrix_range<u_matrix >& J_out) {
66
67 if (J_out.size1() != 6 || J_in.size1() != 6 || J_in.size2() != J_out.size2())
68 return -1;
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);
72 Twist arg;
73 for(unsigned int i=0;i<6;++i)
74 arg(i)=Jj_in(i);
75 Twist tmp(T*arg);
76 for(unsigned int i=0;i<6;++i)
77 Jj_out(i)=tmp(i);
78 }
79 return 0;
80}
81
82}
83#endif /* UBLAS_TYPES_HPP_ */
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
std::map< std::string, TreeElement, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, TreeElement > > > SegmentMap
Definition tree.hpp:37
static int changeBase(Eigen::MatrixBase< Derived > &J, const Frame &T)
#define u_matrix