g2o
Loading...
Searching...
No Matches
isometry3d_mappings.cpp
Go to the documentation of this file.
1// g2o - General Graph Optimization
2// Copyright (C) 2011 H. Strasdat, G. Grisetti, R. Kümmerle, W. Burgard
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
7// met:
8//
9// * Redistributions of source code must retain the above copyright notice,
10// this list of conditions and the following disclaimer.
11// * Redistributions in binary form must reproduce the above copyright
12// notice, this list of conditions and the following disclaimer in the
13// documentation and/or other materials provided with the distribution.
14//
15// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26
27#include "isometry3d_mappings.h"
28
29#include "g2o/stuff/misc.h"
30
31namespace g2o {
32namespace internal {
33
35 Quaternion q2(q);
36 normalize(q2);
37 return q2;
38}
39
41 q.normalize();
42 if (q.w() < 0) {
43 q.coeffs() *= -1;
44 }
45 return q;
46}
47
48// functions to handle the rotation part
50 Quaternion q(R);
51 const double& q0 = q.w();
52 const double& q1 = q.x();
53 const double& q2 = q.y();
54 const double& q3 = q.z();
55 double roll =
56 std::atan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1 * q1 + q2 * q2));
57 double pitch = std::asin(2 * (q0 * q2 - q3 * q1));
58 double yaw = std::atan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2 * q2 + q3 * q3));
59 return Vector3(roll, pitch, yaw);
60}
61
63 // UNOPTIMIZED
64 double roll = v[0];
65 double pitch = v[1];
66 double yaw = v[2];
67 double sy = std::sin(yaw * cst(0.5));
68 double cy = std::cos(yaw * cst(0.5));
69 double sp = std::sin(pitch * cst(0.5));
70 double cp = std::cos(pitch * cst(0.5));
71 double sr = std::sin(roll * cst(0.5));
72 double cr = std::cos(roll * cst(0.5));
73 double w = cr * cp * cy + sr * sp * sy;
74 double x = sr * cp * cy - cr * sp * sy;
75 double y = cr * sp * cy + sr * cp * sy;
76 double z = cr * cp * sy - sr * sp * cy;
77 return Quaternion(w, x, y, z).toRotationMatrix();
78}
79
81 Quaternion q(R);
82 normalize(q);
83 // return (x,y,z) of the quaternion
84 return q.coeffs().head<3>();
85}
86
88 double w = 1 - v.squaredNorm();
89 if (w < 0)
90 return Matrix3::Identity();
91 else
92 w = sqrt(w);
93 return Quaternion(w, v[0], v[1], v[2]).toRotationMatrix();
94}
95
96// functions to handle the toVector of the whole transformations
98 Vector6 v;
99 v.block<3, 1>(3, 0) = toCompactQuaternion(extractRotation(t));
100 v.block<3, 1>(0, 0) = t.translation();
101 return v;
102}
103
105 Vector6 v;
106 v.block<3, 1>(3, 0) = toEuler(extractRotation(t));
107 v.block<3, 1>(0, 0) = t.translation();
108 return v;
109}
110
113 q.normalize();
114 Vector7 v;
115 v[3] = q.x();
116 v[4] = q.y();
117 v[5] = q.z();
118 v[6] = q.w();
119 v.block<3, 1>(0, 0) = t.translation();
120 return v;
121}
122
124 Isometry3 t;
125 t = fromCompactQuaternion(v.block<3, 1>(3, 0));
126 t.translation() = v.block<3, 1>(0, 0);
127 return t;
128}
129
131 Isometry3 t;
132 t = fromEuler(v.block<3, 1>(3, 0));
133 t.translation() = v.block<3, 1>(0, 0);
134 return t;
135}
136
138 Isometry3 t;
139 t = Quaternion(v[6], v[3], v[4], v[5]).toRotationMatrix();
140 t.translation() = v.head<3>();
141 return t;
142}
143
145 SE3Quat result(t.matrix().topLeftCorner<3, 3>(), t.translation());
146 return result;
147}
148
150 Isometry3 result = (Isometry3)t.rotation();
151 result.translation() = t.translation();
152 return result;
153}
154
155} // end namespace internal
156} // end namespace g2o
const Quaternion & rotation() const
Definition se3quat.h:93
const Vector3 & translation() const
Definition se3quat.h:89
some general case utility functions
Isometry3 fromVectorQT(const Vector7 &v)
SE3Quat toSE3Quat(const Isometry3 &t)
Vector3 toEuler(const Matrix3 &R)
Isometry3 fromVectorMQT(const Vector6 &v)
Vector6 toVectorMQT(const Isometry3 &t)
Vector3 toCompactQuaternion(const Matrix3 &R)
Quaternion normalized(const Quaternion &q)
Matrix3 fromCompactQuaternion(const Vector3 &v)
Quaternion & normalize(Quaternion &q)
Matrix3 fromEuler(const Vector3 &v)
Vector6 toVectorET(const Isometry3 &t)
Vector7 toVectorQT(const Isometry3 &t)
Isometry3 fromVectorET(const Vector6 &v)
Isometry3 fromSE3Quat(const SE3Quat &t)
Isometry3::ConstLinearPart extractRotation(const Isometry3 &A)
VectorN< 3 > Vector3
Definition eigen_types.h:51
VectorN< 7 > Vector7
Definition eigen_types.h:54
MatrixN< 3 > Matrix3
Definition eigen_types.h:72
constexpr double cst(long double v)
Definition misc.h:60
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77
VectorN< 6 > Vector6
Definition eigen_types.h:53
Eigen::Quaternion< double > Quaternion
Definition eigen_types.h:81