Rot2.h
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 
19 #pragma once
20 
21 #include <gtsam/geometry/Point2.h>
22 #include <gtsam/base/Lie.h>
23 #include <boost/optional.hpp>
24 
25 #include <random>
26 
27 namespace gtsam {
28 
35  class GTSAM_EXPORT Rot2 : public LieGroup<Rot2, 1> {
36 
38  double c_, s_;
39 
41  Rot2& normalize();
42 
44  inline Rot2(double c, double s) : c_(c), s_(s) {}
45 
46  public:
47 
50 
52  Rot2() : c_(1.0), s_(0.0) {}
53 
55  Rot2(double theta) : c_(cos(theta)), s_(sin(theta)) {}
56 
58  static Rot2 fromAngle(double theta) {
59  return Rot2(theta);
60  }
61 
63  static Rot2 fromDegrees(double theta) {
64  static const double degree = M_PI / 180;
65  return fromAngle(theta * degree);
66  }
67 
69  static Rot2 fromCosSin(double c, double s);
70 
78  static Rot2 relativeBearing(const Point2& d, OptionalJacobian<1,2> H =
79  boost::none);
80 
82  static Rot2 atan2(double y, double x);
83 
90  static Rot2 Random(std::mt19937 & rng);
91 
95 
97  void print(const std::string& s = "theta") const;
98 
100  bool equals(const Rot2& R, double tol = 1e-9) const;
101 
105 
107  inline static Rot2 identity() { return Rot2(); }
108 
110  Rot2 inverse() const { return Rot2(c_, -s_);}
111 
113  Rot2 operator*(const Rot2& R) const {
114  return fromCosSin(c_ * R.c_ - s_ * R.s_, s_ * R.c_ + c_ * R.s_);
115  }
116 
120 
122  static Rot2 Expmap(const Vector1& v, ChartJacobian H = boost::none);
123 
125  static Vector1 Logmap(const Rot2& r, ChartJacobian H = boost::none);
126 
128  Matrix1 AdjointMap() const { return I_1x1; }
129 
131  static Matrix ExpmapDerivative(const Vector& /*v*/) {
132  return I_1x1;
133  }
134 
136  static Matrix LogmapDerivative(const Vector& /*v*/) {
137  return I_1x1;
138  }
139 
140  // Chart at origin simply uses exponential map and its inverse
141  struct ChartAtOrigin {
142  static Rot2 Retract(const Vector1& v, ChartJacobian H = boost::none) {
143  return Expmap(v, H);
144  }
145  static Vector1 Local(const Rot2& r, ChartJacobian H = boost::none) {
146  return Logmap(r, H);
147  }
148  };
149 
150  using LieGroup<Rot2, 1>::inverse; // version with derivative
151 
155 
159  Point2 rotate(const Point2& p, OptionalJacobian<2, 1> H1 = boost::none,
160  OptionalJacobian<2, 2> H2 = boost::none) const;
161 
163  inline Point2 operator*(const Point2& p) const {
164  return rotate(p);
165  }
166 
170  Point2 unrotate(const Point2& p, OptionalJacobian<2, 1> H1 = boost::none,
171  OptionalJacobian<2, 2> H2 = boost::none) const;
172 
176 
178  inline Point2 unit() const {
179  return Point2(c_, s_);
180  }
181 
183  double theta() const {
184  return ::atan2(s_, c_);
185  }
186 
188  double degrees() const {
189  const double degree = M_PI / 180;
190  return theta() / degree;
191  }
192 
194  inline double c() const {
195  return c_;
196  }
197 
199  inline double s() const {
200  return s_;
201  }
202 
204  Matrix2 matrix() const;
205 
207  Matrix2 transpose() const;
208 
209  private:
211  friend class boost::serialization::access;
212  template<class ARCHIVE>
213  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
214  ar & BOOST_SERIALIZATION_NVP(c_);
215  ar & BOOST_SERIALIZATION_NVP(s_);
216  }
217 
218  };
219 
220  template<>
221  struct traits<Rot2> : public internal::LieGroup<Rot2> {};
222 
223  template<>
224  struct traits<const Rot2> : public internal::LieGroup<Rot2> {};
225 
226 } // gtsam
Point3_ unrotate(const Rot3_ &x, const Point3_ &p)
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
static Matrix ExpmapDerivative(const Vector &)
Left-trivialized derivative of the exponential map.
Definition: Rot2.h:131
Scalar * y
double s_
Definition: Rot2.h:38
double degrees() const
Definition: Rot2.h:188
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
static std::mt19937 rng
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
#define M_PI
Definition: main.h:78
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
static Vector1 Local(const Rot2 &r, ChartJacobian H=boost::none)
Definition: Rot2.h:145
static Matrix LogmapDerivative(const Vector &)
Left-trivialized derivative inverse of the exponential map.
Definition: Rot2.h:136
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
Rot2 theta
static Rot2 fromDegrees(double theta)
Named constructor from angle in degrees.
Definition: Rot2.h:63
static void normalize(Signature::Row &row)
Definition: Signature.cpp:158
const double degree
EIGEN_DEVICE_FUNC const CosReturnType cos() const
static Rot2 identity()
Definition: Rot2.h:107
Eigen::VectorXd Vector
Definition: Vector.h:38
Rot2(double c, double s)
Definition: Rot2.h:44
double theta() const
Definition: Rot2.h:183
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
Point2 unit() const
Creates a unit vector as a Point2.
Definition: Rot2.h:178
Matrix1 AdjointMap() const
Definition: Rot2.h:128
double s() const
Definition: Rot2.h:199
Base class and basic functions for Lie types.
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
Definition: jet.h:556
traits
Definition: chartTesting.h:28
Point2 operator*(const Point2 &p) const
Definition: Rot2.h:163
Rot2()
Definition: Rot2.h:52
Both LieGroupTraits and Testable.
Definition: Lie.h:228
float * p
Rot2 operator*(const Rot2 &R) const
Definition: Rot2.h:113
static Rot2 fromAngle(double theta)
Named constructor from angle in radians.
Definition: Rot2.h:58
void serialize(ARCHIVE &ar, const unsigned int)
Definition: Rot2.h:213
EIGEN_DEVICE_FUNC const SinReturnType sin() const
const G double tol
Definition: Group.h:83
Rot2(double theta)
Constructor from angle in radians == exponential map at identity.
Definition: Rot2.h:55
double c() const
Definition: Rot2.h:194
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
The matrix class, also used for vectors and row-vectors.
static Rot2 Retract(const Vector1 &v, ChartJacobian H=boost::none)
Definition: Rot2.h:142
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
Rot2 inverse() const
Definition: Rot2.h:110
2D Point
double c_
Definition: Rot2.h:38


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