conversions.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
31 #include <algorithm>
32 
35 
36 namespace Eigen
37 {
38 Eigen::VectorXd VectorTransform(double px, double py, double pz, double qx, double qy, double qz, double qw)
39 {
40  Eigen::VectorXd ret((Eigen::VectorXd(7) << px, py, pz, qx, qy, qz, qw).finished());
41  return ret;
42 }
43 
44 Eigen::VectorXd IdentityTransform()
45 {
46  return VectorTransform();
47 }
48 } // namespace Eigen
49 
50 namespace exotica
51 {
53 {
54  switch (val.rows())
55  {
56  case 7:
57  {
58  double norm = val.tail(4).norm();
59  if (norm <= 0.0) ThrowPretty("Invalid quaternion!");
60  return KDL::Frame(KDL::Rotation::Quaternion(val(3) / norm, val(4) / norm, val(5) / norm, val(6) / norm), KDL::Vector(val(0), val(1), val(2)));
61  }
62  case 6:
63  return KDL::Frame(KDL::Rotation::RPY(val(3), val(4), val(5)), KDL::Vector(val(0), val(1), val(2)));
64  case 3:
65  return KDL::Frame(KDL::Vector(val(0), val(1), val(2)));
66  default:
67  ThrowPretty("Eigen vector has incorrect length! (" + std::to_string(val.rows()) + ")");
68  }
69 }
70 
72 {
73  switch (val.cols())
74  {
75  case 1:
76  return GetFrame(val);
77  case 4:
78  switch (val.rows())
79  {
80  case 3:
81  case 4:
82  return KDL::Frame(KDL::Rotation(val(0, 0), val(0, 1), val(0, 2), val(1, 0), val(1, 1), val(1, 2), val(2, 0), val(2, 1), val(2, 2)), KDL::Vector(val(0, 3), val(1, 3), val(2, 3)));
83  default:
84  ThrowPretty("Eigen matrix has incorrect number of rows! (" + std::to_string(val.rows()) + ")");
85  }
86  default:
87  ThrowPretty("Eigen matrix has incorrect number of columns! (" + std::to_string(val.cols()) + ")");
88  }
89 }
90 
91 Eigen::MatrixXd GetFrame(const KDL::Frame& val)
92 {
93  Eigen::Isometry3d ret;
94  tf::transformKDLToEigen(val, ret);
95  return ret.matrix();
96 }
97 
98 Eigen::VectorXd GetFrameAsVector(const KDL::Frame& val, RotationType type)
99 {
100  const int rotation_length = GetRotationTypeLength(type);
101  Eigen::VectorXd ret(3 + rotation_length);
102  ret(0) = val.p[0];
103  ret(1) = val.p[1];
104  ret(2) = val.p[2];
105  ret.segment(3, rotation_length) = SetRotation(val.M, type);
106  return ret;
107 }
108 
109 Eigen::VectorXd GetRotationAsVector(const KDL::Frame& val, RotationType type)
110 {
111  return GetFrameAsVector(val, type).tail(GetRotationTypeLength(type));
112 }
113 
115 {
116  switch (type)
117  {
119  if (data.sum() == 0.0) ThrowPretty("Invalid quaternion transform!");
120  return KDL::Rotation::Quaternion(data(0), data(1), data(2), data(3));
121  case RotationType::RPY:
122  return KDL::Rotation::RPY(data(0), data(1), data(2));
123  case RotationType::ZYX:
124  return KDL::Rotation::EulerZYX(data(0), data(1), data(2));
125  case RotationType::ZYZ:
126  return KDL::Rotation::EulerZYZ(data(0), data(1), data(2));
128  {
129  KDL::Vector axis(data(0), data(1), data(2));
130  double angle = axis.Norm();
131  if (fabs(angle) > 1e-10)
132  {
133  return KDL::Rotation::Rot(axis, angle);
134  }
135  else
136  {
137  return KDL::Rotation();
138  }
139  }
141  if (data.sum() == 0.0) ThrowPretty("Invalid matrix transform!");
142  return KDL::Rotation(data(0), data(1), data(2),
143  data(3), data(4), data(5),
144  data(6), data(7), data(8));
145  default:
146  ThrowPretty("Unknown rotation representation type!");
147  }
148 }
149 
150 Eigen::VectorXd SetRotation(const KDL::Rotation& data, RotationType type)
151 {
152  Eigen::VectorXd ret;
153  switch (type)
154  {
156  ret = Eigen::Quaterniond(Eigen::Map<const Eigen::Matrix3d>(data.data).transpose()).coeffs();
157  return ret;
158  case RotationType::RPY:
159  ret.resize(3);
160  data.GetRPY(ret(0), ret(1), ret(2));
161  return ret;
162  case RotationType::ZYX:
163  ret.resize(3);
164  data.GetEulerZYX(ret(0), ret(1), ret(2));
165  return ret;
166  case RotationType::ZYZ:
167  ret.resize(3);
168  data.GetEulerZYZ(ret(0), ret(1), ret(2));
169  return ret;
171  ret = Eigen::Map<const Eigen::Vector3d>(data.GetRot().data);
172  return ret;
174  ret = Eigen::Map<const Eigen::VectorXd>(data.data, 9);
175  return ret;
176  default:
177  ThrowPretty("Unknown rotation representation type!");
178  }
179 }
180 } // namespace exotica
Eigen
exotica::GetFrame
KDL::Frame GetFrame(Eigen::VectorXdRefConst val)
Definition: conversions.cpp:52
printable.h
Eigen::VectorTransform
Eigen::VectorXd VectorTransform(double px=0.0, double py=0.0, double pz=0.0, double qx=0.0, double qy=0.0, double qz=0.0, double qw=1.0)
Definition: conversions.cpp:38
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
exotica::GetFrameFromMatrix
KDL::Frame GetFrameFromMatrix(Eigen::MatrixXdRefConst val)
Definition: conversions.cpp:71
exotica::RotationType::ZYX
@ ZYX
exotica
Definition: collision_scene.h:46
conversions.h
exotica::RotationType::ANGLE_AXIS
@ ANGLE_AXIS
exotica::GetFrameAsVector
Eigen::VectorXd GetFrameAsVector(const KDL::Frame &val, RotationType type=RotationType::RPY)
Definition: conversions.cpp:98
exotica::RotationType::MATRIX
@ MATRIX
exotica::GetRotation
KDL::Rotation GetRotation(Eigen::VectorXdRefConst data, RotationType type)
Definition: conversions.cpp:114
exotica::RotationType::ZYZ
@ ZYZ
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:53
exotica::RotationType::RPY
@ RPY
Eigen::MatrixXdRefConst
const typedef Eigen::Ref< const Eigen::MatrixXd > & MatrixXdRefConst
Definition: conversions.h:54
exotica::RotationType::QUATERNION
@ QUATERNION
Eigen::IdentityTransform
Eigen::VectorXd IdentityTransform()
Definition: conversions.cpp:44
exotica::GetRotationAsVector
Eigen::VectorXd GetRotationAsVector(const KDL::Frame &val, RotationType type)
Definition: conversions.cpp:109
ThrowPretty
#define ThrowPretty(m)
Definition: exception.h:36
tf::transformKDLToEigen
void transformKDLToEigen(const KDL::Frame &k, Eigen::Affine3d &e)
exotica::SetRotation
Eigen::VectorXd SetRotation(const KDL::Rotation &data, RotationType type)
Definition: conversions.cpp:150
exotica::GetRotationTypeLength
int GetRotationTypeLength(const RotationType &type)
Definition: conversions.h:94
eigen_kdl.h
exotica::RotationType
RotationType
Definition: conversions.h:80


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:43:02