gtsam  4.0.0
gtsam
Unit3.h
1 /* ----------------------------------------------------------------------------
2 
3  * Atlanta, Georgia 30332-0415
4  * All Rights Reserved
5  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
12 /*
13  * @file Unit3.h
14  * @date Feb 02, 2011
15  * @author Can Erdogan
16  * @author Frank Dellaert
17  * @author Alex Trevor
18  * @brief Develop a Unit3 class - basically a point on a unit sphere
19  */
20 
21 #pragma once
22 
23 #include <gtsam/geometry/Point2.h>
24 #include <gtsam/geometry/Point3.h>
25 #include <gtsam/base/Manifold.h>
26 #include <gtsam/base/Matrix.h>
27 #include <gtsam/dllexport.h>
28 
29 #include <boost/optional.hpp>
30 #include <boost/random/mersenne_twister.hpp>
31 #include <boost/serialization/nvp.hpp>
32 
33 #include <string>
34 
35 #ifdef GTSAM_USE_TBB
36 #include <tbb/mutex.h>
37 #endif
38 
39 namespace gtsam {
40 
42 class GTSAM_EXPORT Unit3 {
43 
44 private:
45 
46  Vector3 p_;
47  mutable boost::optional<Matrix32> B_;
48  mutable boost::optional<Matrix62> H_B_;
49 
50 #ifdef GTSAM_USE_TBB
51  mutable tbb::mutex B_mutex_;
52 #endif
53 
54 public:
55 
56  enum {
57  dimension = 2
58  };
59 
62 
64  Unit3() :
65  p_(1.0, 0.0, 0.0) {
66  }
67 
69  explicit Unit3(const Vector3& p) :
70  p_(p.normalized()) {
71  }
72 
74  Unit3(double x, double y, double z) :
75  p_(x, y, z) {
76  p_.normalize();
77  }
78 
81  explicit Unit3(const Point2& p, double f) : p_(p.x(), p.y(), f) {
82  p_.normalize();
83  }
84 
86  Unit3(const Unit3& u) {
87  p_ = u.p_;
88  }
89 
91  Unit3& operator=(const Unit3 & u) {
92  p_ = u.p_;
93  return *this;
94  }
95 
97  static Unit3 FromPoint3(const Point3& point, //
98  OptionalJacobian<2, 3> H = boost::none);
99 
101  static Unit3 Random(boost::mt19937 & rng);
102 
104 
107 
108  friend std::ostream& operator<<(std::ostream& os, const Unit3& pair);
109 
111  void print(const std::string& s = std::string()) const;
112 
114  bool equals(const Unit3& s, double tol = 1e-9) const {
115  return equal_with_abs_tol(p_, s.p_, tol);
116  }
118 
121 
128  const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const;
129 
131  Matrix3 skew() const;
132 
134  Point3 point3(OptionalJacobian<3, 2> H = boost::none) const;
135 
137  Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const;
138 
140  friend Point3 operator*(double s, const Unit3& d) {
141  return Point3(s * d.p_);
142  }
143 
145  double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, //
146  OptionalJacobian<1,2> H2 = boost::none) const;
147 
150  Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const;
151 
154  Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, //
155  OptionalJacobian<2, 2> H_q = boost::none) const;
156 
158  double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const;
159 
161  Unit3 cross(const Unit3& q) const {
162  return Unit3(p_.cross(q.p_));
163  }
164 
166  Point3 cross(const Point3& q) const {
167  return point3().cross(q);
168  }
169 
171 
174 
176  inline static size_t Dim() {
177  return 2;
178  }
179 
181  inline size_t dim() const {
182  return 2;
183  }
184 
187  RENORM
188  };
189 
191  Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const;
192 
194  Vector2 localCoordinates(const Unit3& s) const;
195 
197 
198 private:
199 
202 
203  friend class boost::serialization::access;
204  template<class ARCHIVE>
205  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
206  ar & BOOST_SERIALIZATION_NVP(p_);
207  }
208 
210 
211 public:
212  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
213 };
214 
215 // Define GTSAM traits
216 template<> struct traits<Unit3> : public internal::Manifold<Unit3> {
217 };
218 
219 template<> struct traits<const Unit3> : public internal::Manifold<Unit3> {
220 };
221 
222 } // namespace gtsam
223 
bool equals(const Unit3 &s, double tol=1e-9) const
The equals function with tolerance.
Definition: Unit3.h:114
Base class and basic functions for Manifold types.
double dot(const V1 &a, const V2 &b)
Dot product.
Definition: Vector.h:162
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
Unit3(const Unit3 &u)
Copy constructor.
Definition: Unit3.h:86
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
Definition: Point3.h:45
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
equals with a tolerance
Definition: Matrix.h:82
static size_t Dim()
Dimensionality of tangent space = 2 DOF.
Definition: Unit3.h:176
Point3 cross(const Point3 &q) const
Cross-product w Point3.
Definition: Unit3.h:166
Unit3(double x, double y, double z)
Construct from x,y,z.
Definition: Unit3.h:74
Unit3(const Vector3 &p)
Construct from point.
Definition: Unit3.h:69
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
2D Point
Use the exponential map to retract.
Definition: Unit3.h:186
CoordinatesMode
Definition: Unit3.h:185
Unit3 cross(const Unit3 &q) const
Cross-product between two Unit3s.
Definition: Unit3.h:161
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
size_t dim() const
Dimensionality of tangent space = 2 DOF.
Definition: Unit3.h:181
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
3D Point
Definition: Point2.h:40
Unit3 & operator=(const Unit3 &u)
Copy assignment.
Definition: Unit3.h:91
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
typedef and functions to augment Eigen's MatrixXd
Point3 cross(const Point3 &q, OptionalJacobian< 3, 3 > H_p=boost::none, OptionalJacobian< 3, 3 > H_q=boost::none) const
cross product
Definition: Point3.cpp:49
Unit3(const Point2 &p, double f)
Construct from 2D point in plane at focal length f Unit3(p,1) can be viewed as normalized homogeneous...
Definition: Unit3.h:81
Point2 operator *(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:170
Unit3()
Default constructor.
Definition: Unit3.h:64