Rot3.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
22 #include <gtsam/geometry/Rot3.h>
23 #include <gtsam/geometry/SO3.h>
24 #include <boost/math/constants/constants.hpp>
25 
26 #include <cmath>
27 #include <random>
28 
29 using namespace std;
30 
31 namespace gtsam {
32 
33 /* ************************************************************************* */
34 void Rot3::print(const std::string& s) const {
35  cout << (s.empty() ? "R: " : s + " ");
36  gtsam::print(static_cast<Matrix>(matrix()));
37 }
38 
39 /* ************************************************************************* */
40 Rot3 Rot3::Random(std::mt19937& rng) {
41  Unit3 axis = Unit3::Random(rng);
42  uniform_real_distribution<double> randomAngle(-M_PI, M_PI);
43  double angle = randomAngle(rng);
44  return AxisAngle(axis, angle);
45 }
46 
47 
48 
49 /* ************************************************************************* */
50 Rot3 Rot3::AlignPair(const Unit3& axis, const Unit3& a_p, const Unit3& b_p) {
51  // if a_p is already aligned with b_p, return the identity rotation
52  if (std::abs(a_p.dot(b_p)) > 0.999999999) {
53  return Rot3();
54  }
55 
56  // Check axis was not degenerate cross product
57  const Vector3 z = axis.unitVector();
58  if (z.hasNaN())
59  throw std::runtime_error("AlignSinglePair: axis has Nans");
60 
61  // Now, calculate rotation that takes b_p to a_p
62  const Matrix3 P = I_3x3 - z * z.transpose(); // orthogonal projector
63  const Vector3 a_po = P * a_p.unitVector(); // point in a orthogonal to axis
64  const Vector3 b_po = P * b_p.unitVector(); // point in b orthogonal to axis
65  const Vector3 x = a_po.normalized(); // x-axis in axis-orthogonal plane, along a_p vector
66  const Vector3 y = z.cross(x); // y-axis in axis-orthogonal plane
67  const double u = x.dot(b_po); // x-coordinate for b_po
68  const double v = y.dot(b_po); // y-coordinate for b_po
69  double angle = std::atan2(v, u);
70  return Rot3::AxisAngle(z, -angle);
71 }
72 
73 /* ************************************************************************* */
74 Rot3 Rot3::AlignTwoPairs(const Unit3& a_p, const Unit3& b_p, //
75  const Unit3& a_q, const Unit3& b_q) {
76  // there are three frames in play:
77  // a: the first frame in which p and q are measured
78  // b: the second frame in which p and q are measured
79  // i: intermediate, after aligning first pair
80 
81  // First, find rotation around that aligns a_p and b_p
82  Rot3 i_R_b = AlignPair(a_p.cross(b_p), a_p, b_p);
83 
84  // Rotate points in frame b to the intermediate frame,
85  // in which we expect the point p to be aligned now
86  Unit3 i_q = i_R_b * b_q;
87  assert(assert_equal(a_p, i_R_b * b_p, 1e-6));
88 
89  // Now align second pair: we need to align i_q to a_q
90  Rot3 a_R_i = AlignPair(a_p, a_q, i_q);
91  assert(assert_equal(a_p, a_R_i * a_p, 1e-6));
92  assert(assert_equal(a_q, a_R_i * i_q, 1e-6));
93 
94  // The desired rotation is the product of both
95  Rot3 a_R_b = a_R_i * i_R_b;
96  return a_R_b;
97 }
98 
99 /* ************************************************************************* */
100 bool Rot3::equals(const Rot3 & R, double tol) const {
101  return equal_with_abs_tol(matrix(), R.matrix(), tol);
102 }
103 
104 /* ************************************************************************* */
106  return rotate(p);
107 }
108 
109 /* ************************************************************************* */
112  Matrix32 Dp;
113  Unit3 q = Unit3(rotate(p.point3(Hp ? &Dp : 0)));
114  if (Hp) *Hp = q.basis().transpose() * matrix() * Dp;
115  if (HR) *HR = -q.basis().transpose() * matrix() * p.skew();
116  return q;
117 }
118 
119 /* ************************************************************************* */
122  Matrix32 Dp;
123  Unit3 q = Unit3(unrotate(p.point3(Dp)));
124  if (Hp) *Hp = q.basis().transpose() * matrix().transpose () * Dp;
125  if (HR) *HR = q.basis().transpose() * q.skew();
126  return q;
127 }
128 
129 /* ************************************************************************* */
130 Unit3 Rot3::operator*(const Unit3& p) const {
131  return rotate(p);
132 }
133 
134 /* ************************************************************************* */
135 // see doc/math.lyx, SO(3) section
137  OptionalJacobian<3,3> H2) const {
138  const Matrix3& Rt = transpose();
139  Point3 q(Rt * p); // q = Rt*p
140  const double wx = q.x(), wy = q.y(), wz = q.z();
141  if (H1)
142  *H1 << 0.0, -wz, +wy, +wz, 0.0, -wx, -wy, +wx, 0.0;
143  if (H2)
144  *H2 = Rt;
145  return q;
146 }
147 
148 /* ************************************************************************* */
149 Point3 Rot3::column(int index) const{
150  if(index == 3)
151  return r3();
152  else if(index == 2)
153  return r2();
154  else if(index == 1)
155  return r1(); // default returns r1
156  else
157  throw invalid_argument("Argument to Rot3::column must be 1, 2, or 3");
158 }
159 
160 /* ************************************************************************* */
161 Vector3 Rot3::xyz(OptionalJacobian<3, 3> H) const {
162  Matrix3 I;Vector3 q;
163  if (H) {
164  Matrix93 mH;
165  const auto m = matrix();
166 #ifdef GTSAM_USE_QUATERNIONS
167  SO3{m}.vec(mH);
168 #else
169  rot_.vec(mH);
170 #endif
171 
172  Matrix39 qHm;
173  boost::tie(I, q) = RQ(m, qHm);
174 
175  // TODO : Explore whether this expression can be optimized as both
176  // qHm and mH are super-sparse
177  *H = qHm * mH;
178  } else
179  boost::tie(I, q) = RQ(matrix());
180  return q;
181 }
182 
183 /* ************************************************************************* */
184 Vector3 Rot3::ypr(OptionalJacobian<3, 3> H) const {
185  Vector3 q = xyz(H);
186  if (H) H->row(0).swap(H->row(2));
187 
188  return Vector3(q(2),q(1),q(0));
189 }
190 
191 /* ************************************************************************* */
192 Vector3 Rot3::rpy(OptionalJacobian<3, 3> H) const { return xyz(H); }
193 
194 /* ************************************************************************* */
195 double Rot3::roll(OptionalJacobian<1, 3> H) const {
196  double r;
197  if (H) {
198  Matrix3 xyzH;
199  r = xyz(xyzH)(0);
200  *H = xyzH.row(0);
201  } else
202  r = xyz()(0);
203  return r;
204 }
205 
206 /* ************************************************************************* */
207 double Rot3::pitch(OptionalJacobian<1, 3> H) const {
208  double p;
209  if (H) {
210  Matrix3 xyzH;
211  p = xyz(xyzH)(1);
212  *H = xyzH.row(1);
213  } else
214  p = xyz()(1);
215  return p;
216 }
217 
218 /* ************************************************************************* */
219 double Rot3::yaw(OptionalJacobian<1, 3> H) const {
220  double y;
221  if (H) {
222  Matrix3 xyzH;
223  y = xyz(xyzH)(2);
224  *H = xyzH.row(2);
225  } else
226  y = xyz()(2);
227  return y;
228 }
229 
230 /* ************************************************************************* */
232  gtsam::Quaternion q = toQuaternion();
233  Vector v(4);
234  v(0) = q.w();
235  v(1) = q.x();
236  v(2) = q.y();
237  v(3) = q.z();
238  return v;
239 }
240 
241 /* ************************************************************************* */
242 pair<Unit3, double> Rot3::axisAngle() const {
243  const Vector3 omega = Rot3::Logmap(*this);
244  return std::pair<Unit3, double>(Unit3(omega), omega.norm());
245 }
246 
247 /* ************************************************************************* */
248 Matrix3 Rot3::ExpmapDerivative(const Vector3& x) {
249  return SO3::ExpmapDerivative(x);
250 }
251 
252 /* ************************************************************************* */
253 Matrix3 Rot3::LogmapDerivative(const Vector3& x) {
254  return SO3::LogmapDerivative(x);
255 }
256 
257 /* ************************************************************************* */
258 pair<Matrix3, Vector3> RQ(const Matrix3& A, OptionalJacobian<3, 9> H) {
259  const double x = -atan2(-A(2, 1), A(2, 2));
260  const auto Qx = Rot3::Rx(-x).matrix();
261  const Matrix3 B = A * Qx;
262 
263  const double y = -atan2(B(2, 0), B(2, 2));
264  const auto Qy = Rot3::Ry(-y).matrix();
265  const Matrix3 C = B * Qy;
266 
267  const double z = -atan2(-C(1, 0), C(1, 1));
268  const auto Qz = Rot3::Rz(-z).matrix();
269  const Matrix3 R = C * Qz;
270 
271  if (H) {
272  if (std::abs(y - M_PI / 2) < 1e-2)
273  throw std::runtime_error(
274  "Rot3::RQ : Derivative undefined at singularity (gimbal lock)");
275 
276  auto atan_d1 = [](double y, double x) { return x / (x * x + y * y); };
277  auto atan_d2 = [](double y, double x) { return -y / (x * x + y * y); };
278 
279  const auto sx = -Qx(2, 1), cx = Qx(1, 1);
280  const auto sy = -Qy(0, 2), cy = Qy(0, 0);
281 
282  *H = Matrix39::Zero();
283  // First, calculate the derivate of x
284  (*H)(0, 5) = atan_d1(A(2, 1), A(2, 2));
285  (*H)(0, 8) = atan_d2(A(2, 1), A(2, 2));
286 
287  // Next, calculate the derivate of y. We have
288  // b20 = a20 and b22 = a21 * sx + a22 * cx
289  (*H)(1, 2) = -atan_d1(B(2, 0), B(2, 2));
290  const auto yHb22 = -atan_d2(B(2, 0), B(2, 2));
291  (*H)(1, 5) = yHb22 * sx;
292  (*H)(1, 8) = yHb22 * cx;
293 
294  // Next, calculate the derivate of z. We have
295  // c20 = a10 * cy + a11 * sx * sy + a12 * cx * sy
296  // c22 = a11 * cx - a12 * sx
297  const auto c10Hx = (A(1, 1) * cx - A(1, 2) * sx) * sy;
298  const auto c10Hy = A(1, 2) * cx * cy + A(1, 1) * cy * sx - A(1, 0) * sy;
299  Vector9 c10HA = c10Hx * H->row(0) + c10Hy * H->row(1);
300  c10HA[1] = cy;
301  c10HA[4] = sx * sy;
302  c10HA[7] = cx * sy;
303 
304  const auto c11Hx = -A(1, 2) * cx - A(1, 1) * sx;
305  Vector9 c11HA = c11Hx * H->row(0);
306  c11HA[4] = cx;
307  c11HA[7] = -sx;
308 
309  H->block<1, 9>(2, 0) =
310  atan_d1(C(1, 0), C(1, 1)) * c10HA + atan_d2(C(1, 0), C(1, 1)) * c11HA;
311  }
312 
313  const auto xyz = Vector3(x, y, z);
314  return make_pair(R, xyz);
315 }
316 
317 /* ************************************************************************* */
318 ostream &operator<<(ostream &os, const Rot3& R) {
319  os << R.matrix().format(matlabFormat());
320  return os;
321 }
322 
323 /* ************************************************************************* */
324 Rot3 Rot3::slerp(double t, const Rot3& other) const {
325  return interpolate(*this, other, t);
326 }
327 
328 /* ************************************************************************* */
329 
330 } // namespace gtsam
331 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Matrix3f m
Vector3_ operator*(const Double_ &s, const Vector3_ &v)
GTSAM_EXPORT const Matrix32 & basis(OptionalJacobian< 6, 2 > H=boost::none) const
Definition: Unit3.cpp:76
Scalar * y
EIGEN_DEVICE_FUNC CoeffReturnType x() const
Eigen::Vector3d Vector3
Definition: Vector.h:43
EIGEN_DEVICE_FUNC CoeffReturnType y() const
ArrayXcf v
Definition: Cwise_arg.cpp:1
static std::mt19937 rng
#define M_PI
Definition: main.h:78
Rot2 R(Rot2::fromAngle(0.1))
const double cx
GTSAM_EXPORT Vector3 unitVector(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Vector.
Definition: Unit3.cpp:143
Definition: Half.h:150
Matrix3 matrix() const
Definition: Rot3M.cpp:219
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
3*3 matrix representation of SO(3)
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
void quaternion(void)
EIGEN_DEVICE_FUNC CoeffReturnType w() const
EIGEN_DEVICE_FUNC CoeffReturnType z() const
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
T interpolate(const T &X, const T &Y, double t)
Definition: Lie.h:325
const Eigen::IOFormat & matlabFormat()
Definition: Matrix.cpp:139
pair< Matrix3, Vector3 > RQ(const Matrix3 &A, OptionalJacobian< 3, 9 > H)
Definition: Rot3.cpp:258
Eigen::VectorXd Vector
Definition: Vector.h:38
P unrotate(const T &r, const P &pt)
Definition: lieProxies.h:50
P rotate(const T &r, const P &pt)
Definition: lieProxies.h:47
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
static const double r2
EIGEN_DEVICE_FUNC const Scalar & q
static const Matrix I
Definition: lago.cpp:35
GTSAM_EXPORT Point3 point3(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Point3.
Definition: Unit3.cpp:136
static const double r3
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
Definition: jet.h:556
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:84
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
ostream & operator<<(ostream &os, const Rot3 &R)
Definition: Rot3.cpp:318
static const double r1
ofstream os("timeSchurFactors.csv")
The quaternion class used to represent 3D orientations and rotations.
Unit3 cross(const Unit3 &q) const
Cross-product between two Unit3s.
Definition: Unit3.h:168
GTSAM_EXPORT double dot(const Unit3 &q, OptionalJacobian< 1, 2 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
Return dot product with q.
Definition: Unit3.cpp:166
const double cy
#define HR
Definition: mincover.c:26
float * p
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
#define abs(x)
Definition: datatypes.h:17
const MATRIX::ConstColXpr column(const MATRIX &A, size_t j)
Definition: base/Matrix.h:214
Point2 t(10, 10)
3D rotation represented as a rotation matrix or quaternion
GTSAM_EXPORT Matrix3 skew() const
Return skew-symmetric associated with 3D point on unit sphere.
Definition: Unit3.cpp:161


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:53