gtsam  4.0.0
gtsam
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 namespace gtsam {
26 
33  class GTSAM_EXPORT Rot2 : public LieGroup<Rot2, 1> {
34 
36  double c_, s_;
37 
39  Rot2& normalize();
40 
42  inline Rot2(double c, double s) : c_(c), s_(s) {}
43 
44  public:
45 
48 
50  Rot2() : c_(1.0), s_(0.0) {}
51 
53  Rot2(double theta) : c_(cos(theta)), s_(sin(theta)) {}
54 
56  static Rot2 fromAngle(double theta) {
57  return Rot2(theta);
58  }
59 
61  static Rot2 fromDegrees(double theta) {
62  static const double degree = M_PI / 180;
63  return fromAngle(theta * degree);
64  }
65 
67  static Rot2 fromCosSin(double c, double s);
68 
76  static Rot2 relativeBearing(const Point2& d, OptionalJacobian<1,2> H =
77  boost::none);
78 
80  static Rot2 atan2(double y, double x);
81 
85 
87  void print(const std::string& s = "theta") const;
88 
90  bool equals(const Rot2& R, double tol = 1e-9) const;
91 
95 
97  inline static Rot2 identity() { return Rot2(); }
98 
100  Rot2 inverse() const { return Rot2(c_, -s_);}
101 
103  Rot2 operator*(const Rot2& R) const {
104  return fromCosSin(c_ * R.c_ - s_ * R.s_, s_ * R.c_ + c_ * R.s_);
105  }
106 
110 
112  static Rot2 Expmap(const Vector1& v, ChartJacobian H = boost::none);
113 
115  static Vector1 Logmap(const Rot2& r, ChartJacobian H = boost::none);
116 
118  Matrix1 AdjointMap() const { return I_1x1; }
119 
121  static Matrix ExpmapDerivative(const Vector& /*v*/) {
122  return I_1x1;
123  }
124 
126  static Matrix LogmapDerivative(const Vector& /*v*/) {
127  return I_1x1;
128  }
129 
130  // Chart at origin simply uses exponential map and its inverse
131  struct ChartAtOrigin {
132  static Rot2 Retract(const Vector1& v, ChartJacobian H = boost::none) {
133  return Expmap(v, H);
134  }
135  static Vector1 Local(const Rot2& r, ChartJacobian H = boost::none) {
136  return Logmap(r, H);
137  }
138  };
139 
140  using LieGroup<Rot2, 1>::inverse; // version with derivative
141 
145 
149  Point2 rotate(const Point2& p, OptionalJacobian<2, 1> H1 = boost::none,
150  OptionalJacobian<2, 2> H2 = boost::none) const;
151 
153  inline Point2 operator*(const Point2& p) const {
154  return rotate(p);
155  }
156 
160  Point2 unrotate(const Point2& p, OptionalJacobian<2, 1> H1 = boost::none,
161  OptionalJacobian<2, 2> H2 = boost::none) const;
162 
166 
168  inline Point2 unit() const {
169  return Point2(c_, s_);
170  }
171 
173  double theta() const {
174  return ::atan2(s_, c_);
175  }
176 
178  double degrees() const {
179  const double degree = M_PI / 180;
180  return theta() / degree;
181  }
182 
184  inline double c() const {
185  return c_;
186  }
187 
189  inline double s() const {
190  return s_;
191  }
192 
194  Matrix2 matrix() const;
195 
197  Matrix2 transpose() const;
198 
199  private:
201  friend class boost::serialization::access;
202  template<class ARCHIVE>
203  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
204  ar & BOOST_SERIALIZATION_NVP(c_);
205  ar & BOOST_SERIALIZATION_NVP(s_);
206  }
207 
208  };
209 
210  template<>
211  struct traits<Rot2> : public internal::LieGroup<Rot2> {};
212 
213  template<>
214  struct traits<const Rot2> : public internal::LieGroup<Rot2> {};
215 
216 } // gtsam
static Rot2 fromDegrees(double theta)
Named constructor from angle in degrees.
Definition: Rot2.h:61
double theta() const
return angle (RADIANS)
Definition: Rot2.h:173
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
double c() const
return cos
Definition: Rot2.h:184
Matrix1 AdjointMap() const
Calculate Adjoint map.
Definition: Rot2.h:118
static Matrix ExpmapDerivative(const Vector &)
Left-trivialized derivative of the exponential map.
Definition: Rot2.h:121
Both LieGroupTraits and Testable.
Definition: Lie.h:237
Point3 normalize(const Point3 &p, OptionalJacobian< 3, 3 > H)
normalize, with optional Jacobian
Definition: Point3.cpp:109
static Matrix LogmapDerivative(const Vector &)
Left-trivialized derivative inverse of the exponential map.
Definition: Rot2.h:126
Template to create a binary predicate.
Definition: Testable.h:110
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Rot2()
default constructor, zero rotation
Definition: Rot2.h:50
Definition: Rot2.h:131
2D Point
A CRTP helper class that implements Lie group methods Prerequisites: methods operator*,...
Definition: Lie.h:36
Definition: Rot2.h:33
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
double degrees() const
return angle (DEGREES)
Definition: Rot2.h:178
Definition: Point2.h:40
Point2 unit() const
Creates a unit vector as a Point2.
Definition: Rot2.h:168
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
static Rot2 fromAngle(double theta)
Named constructor from angle in radians.
Definition: Rot2.h:56
Base class and basic functions for Lie types.
Rot2 inverse() const
The inverse rotation - negative angle.
Definition: Rot2.h:100
Rot2(double theta)
Constructor from angle in radians == exponential map at identity.
Definition: Rot2.h:53
static Rot2 identity()
identity
Definition: Rot2.h:97
Point2 operator *(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:170
double s() const
return sin
Definition: Rot2.h:189