Rot3Q.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 
18 #include <gtsam/config.h> // Get GTSAM_USE_QUATERNIONS macro
19 
20 #ifdef GTSAM_USE_QUATERNIONS
21 
22 #include <gtsam/geometry/Rot3.h>
23 #include <boost/math/constants/constants.hpp>
24 #include <cmath>
25 
26 using namespace std;
27 
28 namespace gtsam {
29 
30  /* ************************************************************************* */
31  Rot3::Rot3() : quaternion_(Quaternion::Identity()) {}
32 
33  /* ************************************************************************* */
34  Rot3::Rot3(const Point3& col1, const Point3& col2, const Point3& col3) :
35  quaternion_((Matrix3() <<
36  col1.x(), col2.x(), col3.x(),
37  col1.y(), col2.y(), col3.y(),
38  col1.z(), col2.z(), col3.z()).finished()) {}
39 
40  /* ************************************************************************* */
41  Rot3::Rot3(double R11, double R12, double R13,
42  double R21, double R22, double R23,
43  double R31, double R32, double R33) :
44  quaternion_((Matrix3() <<
45  R11, R12, R13,
46  R21, R22, R23,
47  R31, R32, R33).finished()) {}
48 
49  /* ************************************************************************* */
51  quaternion_(q) {
52  }
53 
54  /* ************************************************************************* */
55  Rot3 Rot3::Rx(double t) {
56  return gtsam::Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitX()));
57  }
58 
59  /* ************************************************************************* */
60  Rot3 Rot3::Ry(double t) {
61  return gtsam::Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitY()));
62  }
63 
64  /* ************************************************************************* */
65  Rot3 Rot3::Rz(double t) {
66  return gtsam::Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitZ()));
67  }
68 
69  /* ************************************************************************* */
70  Rot3 Rot3::RzRyRx(double x, double y, double z, OptionalJacobian<3, 1> Hx,
71  OptionalJacobian<3, 1> Hy, OptionalJacobian<3, 1> Hz) {
72  if (Hx) (*Hx) << 1, 0, 0;
73 
74  if (Hy or Hz) {
75  const auto cx = cos(x), sx = sin(x);
76  if (Hy) (*Hy) << 0, cx, -sx;
77  if (Hz) {
78  const auto cy = cos(y), sy = sin(y);
79  (*Hz) << -sy, sx * cy, cx * cy;
80  }
81  }
82 
83  return Rot3(
84  gtsam::Quaternion(Eigen::AngleAxisd(z, Eigen::Vector3d::UnitZ())) *
85  gtsam::Quaternion(Eigen::AngleAxisd(y, Eigen::Vector3d::UnitY())) *
86  gtsam::Quaternion(Eigen::AngleAxisd(x, Eigen::Vector3d::UnitX())));
87  }
88 
89  /* ************************************************************************* */
90  Rot3 Rot3::normalized() const {
91  return Rot3(quaternion_.normalized());
92  }
93  /* ************************************************************************* */
94  Rot3 Rot3::operator*(const Rot3& R2) const {
95  return Rot3(quaternion_ * R2.quaternion_);
96  }
97 
98  /* ************************************************************************* */
99  // TODO: Maybe use return type `const Eigen::Transpose<const Matrix3>`?
100  // It works in Rot3M but not here, because of some weird behavior
101  // due to Eigen's expression templates which needs more investigation.
102  // For example, if we use matrix(), the value returned has a 1e-10,
103  // and if we use quaternion_.toRotationMatrix(), the matrix is arbitrary.
104  // Using eval() here doesn't help, it only helps if we use it in
105  // the downstream code.
106  Matrix3 Rot3::transpose() const {
107  return matrix().transpose();
108  }
109 
110  /* ************************************************************************* */
111  Point3 Rot3::rotate(const Point3& p,
112  OptionalJacobian<3,3> H1, OptionalJacobian<3,3> H2) const {
113  const Matrix3 R = matrix();
114  if (H1) *H1 = R * skewSymmetric(-p.x(), -p.y(), -p.z());
115  if (H2) *H2 = R;
116  const Vector3 r = R * p;
117  return Point3(r.x(), r.y(), r.z());
118  }
119 
120  /* ************************************************************************* */
121  Vector3 Rot3::Logmap(const Rot3& R, OptionalJacobian<3, 3> H) {
122  return traits<gtsam::Quaternion>::Logmap(R.quaternion_, H);
123  }
124 
125  /* ************************************************************************* */
128  if (mode == Rot3::EXPMAP) return Expmap(omega, H);
129  else throw std::runtime_error("Rot3::Retract: unknown mode");
130  }
131 
132  /* ************************************************************************* */
135  if (mode == Rot3::EXPMAP) return Logmap(R, H);
136  else throw std::runtime_error("Rot3::Local: unknown mode");
137  }
138 
139  /* ************************************************************************* */
140  Matrix3 Rot3::matrix() const {return quaternion_.toRotationMatrix();}
141 
142  /* ************************************************************************* */
143  Point3 Rot3::r1() const { return Point3(quaternion_.toRotationMatrix().col(0)); }
144 
145  /* ************************************************************************* */
146  Point3 Rot3::r2() const { return Point3(quaternion_.toRotationMatrix().col(1)); }
147 
148  /* ************************************************************************* */
149  Point3 Rot3::r3() const { return Point3(quaternion_.toRotationMatrix().col(2)); }
150 
151  /* ************************************************************************* */
152  gtsam::Quaternion Rot3::toQuaternion() const { return quaternion_; }
153 
154  /* ************************************************************************* */
155 
156 } // namespace gtsam
157 
158 #endif
Point3 r1() const
first column
Definition: Rot3M.cpp:224
Scalar * y
Eigen::Vector3d Vector3
Definition: Vector.h:43
Use the Lie group exponential map to retract.
Definition: Rot3.h:343
Rot2 R(Rot2::fromAngle(0.1))
const double cx
Definition: Half.h:150
Matrix3 matrix() const
Definition: Rot3M.cpp:219
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx=boost::none, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hz=boost::none)
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
Definition: Rot3M.cpp:85
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
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Definition: Rot3M.cpp:149
static Vector3 Local(const Rot3 &r, ChartJacobian H=boost::none)
Definition: Rot3M.cpp:211
EIGEN_DEVICE_FUNC const CosReturnType cos() const
static Rot3 Rx(double t)
Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
Definition: Rot3M.cpp:57
OptionalJacobian< N, N > ChartJacobian
Definition: Lie.h:39
Point3 r2() const
second column
Definition: Rot3M.cpp:227
Point3 r3() const
third column
Definition: Rot3M.cpp:230
static Rot3 Retract(const Vector3 &v, ChartJacobian H=boost::none)
Definition: Rot3M.cpp:203
EIGEN_DEVICE_FUNC const Scalar & q
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3.h:377
#define ROT3_DEFAULT_COORDINATES_MODE
Definition: Rot3.h:43
Matrix3 transpose() const
Definition: Rot3M.cpp:144
traits
Definition: chartTesting.h:28
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3M.cpp:158
static Rot3 Rz(double t)
Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
Definition: Rot3M.cpp:75
The quaternion class used to represent 3D orientations and rotations.
Rot3 normalized() const
Definition: Rot3M.cpp:112
const double cy
float * p
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Vector3 Point3
Definition: Point3.h:35
Rot3 operator*(const Rot3 &R2) const
Syntatic sugar for composing two rotations.
Definition: Rot3M.cpp:139
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
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
gtsam::Quaternion toQuaternion() const
Definition: Rot3M.cpp:233
Point2 t(10, 10)
static Rot3 Ry(double t)
Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
Definition: Rot3M.cpp:66
CoordinatesMode
Definition: Rot3.h:342
3D rotation represented as a rotation matrix or quaternion
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion


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