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


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:05:00