Unit3.h
Go to the documentation of this file.
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/serialization/nvp.hpp>
31 
32 #include <random>
33 #include <string>
34 
35 #ifdef GTSAM_USE_TBB
36 #include <mutex> // std::mutex
37 #endif
38 
39 namespace gtsam {
40 
42 class Unit3 {
43 
44 private:
45 
47  mutable boost::optional<Matrix32> B_;
48  mutable boost::optional<Matrix62> H_B_;
49 
50 #ifdef GTSAM_USE_TBB
51  mutable std::mutex B_mutex_;
52 #endif
53 
54 public:
55 
56  enum {
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  B_ = u.B_;
94  H_B_ = u.H_B_;
95  return *this;
96  }
97 
99  GTSAM_EXPORT static Unit3 FromPoint3(const Point3& point, //
100  OptionalJacobian<2, 3> H = boost::none);
101 
108  GTSAM_EXPORT static Unit3 Random(std::mt19937 & rng);
109 
111 
114 
115  friend std::ostream& operator<<(std::ostream& os, const Unit3& pair);
116 
118  GTSAM_EXPORT void print(const std::string& s = std::string()) const;
119 
121  bool equals(const Unit3& s, double tol = 1e-9) const {
122  return equal_with_abs_tol(p_, s.p_, tol);
123  }
125 
128 
135  GTSAM_EXPORT const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const;
136 
138  GTSAM_EXPORT Matrix3 skew() const;
139 
141  GTSAM_EXPORT Point3 point3(OptionalJacobian<3, 2> H = boost::none) const;
142 
144  GTSAM_EXPORT Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const;
145 
147  friend Point3 operator*(double s, const Unit3& d) {
148  return Point3(s * d.p_);
149  }
150 
152  GTSAM_EXPORT double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, //
153  OptionalJacobian<1,2> H2 = boost::none) const;
154 
157  GTSAM_EXPORT Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const;
158 
161  GTSAM_EXPORT Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, //
162  OptionalJacobian<2, 2> H_q = boost::none) const;
163 
165  GTSAM_EXPORT double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const;
166 
168  Unit3 cross(const Unit3& q) const {
169  return Unit3(p_.cross(q.p_));
170  }
171 
173  Point3 cross(const Point3& q) const {
174  return point3().cross(q);
175  }
176 
178 
181 
183  inline static size_t Dim() {
184  return 2;
185  }
186 
188  inline size_t dim() const {
189  return 2;
190  }
191 
195  };
196 
198  GTSAM_EXPORT Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const;
199 
201  GTSAM_EXPORT Vector2 localCoordinates(const Unit3& s) const;
202 
204 
205 private:
206 
209 
211  template<class ARCHIVE>
212  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
213  ar & BOOST_SERIALIZATION_NVP(p_);
214  }
215 
217 
218 public:
220 };
221 
222 // Define GTSAM traits
223 template<> struct traits<Unit3> : public internal::Manifold<Unit3> {
224 };
225 
226 template<> struct traits<const Unit3> : public internal::Manifold<Unit3> {
227 };
228 
229 } // namespace gtsam
230 
Vector3 p_
The location of the point on the unit sphere.
Definition: Unit3.h:46
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
Unit3(const Unit3 &u)
Copy constructor.
Definition: Unit3.h:86
GTSAM_EXPORT const Matrix32 & basis(OptionalJacobian< 6, 2 > H=boost::none) const
Definition: Unit3.cpp:76
Scalar * y
friend std::ostream & operator<<(std::ostream &os, const Unit3 &pair)
Definition: Unit3.cpp:150
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector2 Point2
Definition: Point2.h:27
GTSAM_EXPORT Unit3 retract(const Vector2 &v, OptionalJacobian< 2, 2 > H=boost::none) const
The retract function.
Definition: Unit3.cpp:247
ArrayXcf v
Definition: Cwise_arg.cpp:1
static std::mt19937 rng
GTSAM_EXPORT Vector2 localCoordinates(const Unit3 &s) const
The local coordinates function.
Definition: Unit3.cpp:277
GTSAM_EXPORT Vector3 unitVector(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Vector.
Definition: Unit3.cpp:143
GTSAM_EXPORT double distance(const Unit3 &q, OptionalJacobian< 1, 2 > H=boost::none) const
Distance between two directions.
Definition: Unit3.cpp:237
Unit3(const Point2 &p, double f)
Definition: Unit3.h:81
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
static GTSAM_EXPORT Unit3 Random(std::mt19937 &rng)
Definition: Unit3.cpp:47
boost::optional< Matrix32 > B_
Cached basis.
Definition: Unit3.h:47
Point3 point(10, 0,-5)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
GTSAM_EXPORT Vector2 errorVector(const Unit3 &q, OptionalJacobian< 2, 2 > H_p=boost::none, OptionalJacobian< 2, 2 > H_q=boost::none) const
Definition: Unit3.cpp:201
Base class and basic functions for Manifold types.
Unit3 & operator=(const Unit3 &u)
Copy assignment.
Definition: Unit3.h:91
static size_t Dim()
Dimensionality of tangent space = 2 DOF.
Definition: Unit3.h:183
Point3 cross(const Point3 &q) const
Cross-product w Point3.
Definition: Unit3.h:173
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
friend Point3 operator*(double s, const Unit3 &d)
Return scaled direction as Point3.
Definition: Unit3.h:147
RealScalar s
EIGEN_DEVICE_FUNC const Scalar & q
Unit3()
Default constructor.
Definition: Unit3.h:64
GTSAM_EXPORT Vector2 error(const Unit3 &q, OptionalJacobian< 2, 2 > H_q=boost::none) const
Definition: Unit3.cpp:191
CoordinatesMode
Definition: Unit3.h:192
GTSAM_EXPORT Point3 point3(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Point3.
Definition: Unit3.cpp:136
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:84
GTSAM_EXPORT void print(const std::string &s=std::string()) const
The print fuction.
Definition: Unit3.cpp:156
traits
Definition: chartTesting.h:28
Retract with vector addition and renormalize.
Definition: Unit3.h:194
Unit3(double x, double y, double z)
Construct from x,y,z.
Definition: Unit3.h:74
ofstream os("timeSchurFactors.csv")
Unit3 cross(const Unit3 &q) const
Cross-product between two Unit3s.
Definition: Unit3.h:168
friend class boost::serialization::access
Definition: Unit3.h:210
GTSAM_EXPORT double dot(const Unit3 &q, OptionalJacobian< 1, 2 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
Return dot product with q.
Definition: Unit3.cpp:166
Unit3(const Vector3 &p)
Construct from point.
Definition: Unit3.h:69
3D Point
float * p
Use the exponential map to retract.
Definition: Unit3.h:193
static GTSAM_EXPORT Unit3 FromPoint3(const Point3 &point, OptionalJacobian< 2, 3 > H=boost::none)
Named constructor from Point3 with optional Jacobian.
Definition: Unit3.cpp:36
size_t dim() const
Dimensionality of tangent space = 2 DOF.
Definition: Unit3.h:188
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
void serialize(ARCHIVE &ar, const unsigned int)
Definition: Unit3.h:212
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
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
boost::optional< Matrix62 > H_B_
Cached basis derivative.
Definition: Unit3.h:48
2D Point
bool equals(const Unit3 &s, double tol=1e-9) const
The equals function with tolerance.
Definition: Unit3.h:121
GTSAM_EXPORT Matrix3 skew() const
Return skew-symmetric associated with 3D point on unit sphere.
Definition: Unit3.cpp:161


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:21