Unit3.cpp
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  * @author Zhaoyang Lv
19  * @brief The Unit3 class - basically a point on a unit sphere
20  */
21 
22 #include <gtsam/geometry/Unit3.h>
23 #include <gtsam/geometry/Point2.h>
24 #include <gtsam/config.h> // for GTSAM_USE_TBB
25 
26 #include <iostream>
27 #include <limits>
28 #include <cmath>
29 #include <vector>
30 
31 using namespace std;
32 
33 namespace gtsam {
34 
35 /* ************************************************************************* */
36 Unit3 Unit3::FromPoint3(const Point3& point, OptionalJacobian<2, 3> H) {
37  // 3*3 Derivative of representation with respect to point is 3*3:
38  Matrix3 D_p_point;
39  Unit3 direction;
40  direction.p_ = normalize(point, H ? &D_p_point : 0);
41  if (H)
42  *H << direction.basis().transpose() * D_p_point;
43  return direction;
44 }
45 
46 /* ************************************************************************* */
47 Unit3 Unit3::Random(std::mt19937& rng) {
48  // http://mathworld.wolfram.com/SpherePointPicking.html
49  // Adapted from implementation in boost, but using std <random>
50  std::uniform_real_distribution<double> uniform(-1.0, 1.0);
51  double sqsum;
52  double x, y;
53  do {
54  x = uniform(rng);
55  y = uniform(rng);
56  sqsum = x * x + y * y;
57  } while (sqsum > 1);
58  const double mult = 2 * sqrt(1 - sqsum);
59  return Unit3(x * mult, y * mult, 2 * sqsum - 1);
60 }
61 
62 /* ************************************************************************* */
63 // Get the axis of rotation with the minimum projected length of the point
64 static Point3 CalculateBestAxis(const Point3& n) {
65  double mx = std::abs(n.x()), my = std::abs(n.y()), mz = std::abs(n.z());
66  if ((mx <= my) && (mx <= mz)) {
67  return Point3(1.0, 0.0, 0.0);
68  } else if ((my <= mx) && (my <= mz)) {
69  return Point3(0.0, 1.0, 0.0);
70  } else {
71  return Point3(0, 0, 1);
72  }
73 }
74 
75 /* ************************************************************************* */
76 const Matrix32& Unit3::basis(OptionalJacobian<6, 2> H) const {
77 #ifdef GTSAM_USE_TBB
78  // NOTE(hayk): At some point it seemed like this reproducably resulted in
79  // deadlock. However, I don't know why and I can no longer reproduce it.
80  // It either was a red herring or there is still a latent bug left to debug.
81  std::unique_lock<std::mutex> lock(B_mutex_);
82 #endif
83 
84  const bool cachedBasis = static_cast<bool>(B_);
85  const bool cachedJacobian = static_cast<bool>(H_B_);
86 
87  if (H) {
88  if (!cachedJacobian) {
89  // Compute Jacobian. Recomputes B_
90  Matrix32 B;
91  Matrix62 jacobian;
92  Matrix33 H_B1_n, H_b1_B1, H_b2_n, H_b2_b1;
93 
94  // Choose the direction of the first basis vector b1 in the tangent plane
95  // by crossing n with the chosen axis.
96  const Point3 n(p_), axis = CalculateBestAxis(n);
97  const Point3 B1 = gtsam::cross(n, axis, &H_B1_n);
98 
99  // Normalize result to get a unit vector: b1 = B1 / |B1|.
100  B.col(0) = normalize(B1, &H_b1_B1);
101 
102  // Get the second basis vector b2, which is orthogonal to n and b1.
103  B.col(1) = gtsam::cross(n, B.col(0), &H_b2_n, &H_b2_b1);
104 
105  // Chain rule tomfoolery to compute the jacobian.
106  const Matrix32& H_n_p = B;
107  jacobian.block<3, 2>(0, 0) = H_b1_B1 * H_B1_n * H_n_p;
108  auto H_b1_p = jacobian.block<3, 2>(0, 0);
109  jacobian.block<3, 2>(3, 0) = H_b2_n * H_n_p + H_b2_b1 * H_b1_p;
110 
111  // Cache the result and jacobian
112  H_B_.reset(jacobian);
113  B_.reset(B);
114  }
115 
116  // Return cached jacobian, possibly computed just above
117  *H = *H_B_;
118  }
119 
120  if (!cachedBasis) {
121  // Same calculation as above, without derivatives.
122  // Done after H block, as that possibly computes B_ for the first time
123  Matrix32 B;
124 
125  const Point3 n(p_), axis = CalculateBestAxis(n);
126  const Point3 B1 = gtsam::cross(n, axis);
127  B.col(0) = normalize(B1);
128  B.col(1) = gtsam::cross(n, B.col(0));
129  B_.reset(B);
130  }
131 
132  return *B_;
133 }
134 
135 /* ************************************************************************* */
137  if (H)
138  *H = basis();
139  return Point3(p_);
140 }
141 
142 /* ************************************************************************* */
143 Vector3 Unit3::unitVector(OptionalJacobian<3, 2> H) const {
144  if (H)
145  *H = basis();
146  return p_;
147 }
148 
149 /* ************************************************************************* */
150 std::ostream& operator<<(std::ostream& os, const Unit3& pair) {
151  os << pair.p_ << endl;
152  return os;
153 }
154 
155 /* ************************************************************************* */
156 void Unit3::print(const std::string& s) const {
157  cout << s << ":" << p_ << endl;
158 }
159 
160 /* ************************************************************************* */
161 Matrix3 Unit3::skew() const {
162  return skewSymmetric(p_.x(), p_.y(), p_.z());
163 }
164 
165 /* ************************************************************************* */
167  OptionalJacobian<1, 2> H_q) const {
168  // Get the unit vectors of each, and the derivative.
169  Matrix32 H_pn_p;
170  Point3 pn = point3(H_p ? &H_pn_p : nullptr);
171 
172  Matrix32 H_qn_q;
173  const Point3 qn = q.point3(H_q ? &H_qn_q : nullptr);
174 
175  // Compute the dot product of the Point3s.
176  Matrix13 H_dot_pn, H_dot_qn;
177  double d = gtsam::dot(pn, qn, H_p ? &H_dot_pn : nullptr, H_q ? &H_dot_qn : nullptr);
178 
179  if (H_p) {
180  (*H_p) << H_dot_pn * H_pn_p;
181  }
182 
183  if (H_q) {
184  (*H_q) = H_dot_qn * H_qn_q;
185  }
186 
187  return d;
188 }
189 
190 /* ************************************************************************* */
192  // 2D error is equal to B'*q, as B is 3x2 matrix and q is 3x1
193  const Vector2 xi = basis().transpose() * q.p_;
194  if (H_q) {
195  *H_q = basis().transpose() * q.basis();
196  }
197  return xi;
198 }
199 
200 /* ************************************************************************* */
201 Vector2 Unit3::errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p,
202  OptionalJacobian<2, 2> H_q) const {
203  // Get the point3 of this, and the derivative.
204  Matrix32 H_qn_q;
205  const Point3 qn = q.point3(H_q ? &H_qn_q : nullptr);
206 
207  // 2D error here is projecting q into the tangent plane of this (p).
208  Matrix62 H_B_p;
209  Matrix23 Bt = basis(H_p ? &H_B_p : nullptr).transpose();
210  Vector2 xi = Bt * qn;
211 
212  if (H_p) {
213  // Derivatives of each basis vector.
214  const Matrix32& H_b1_p = H_B_p.block<3, 2>(0, 0);
215  const Matrix32& H_b2_p = H_B_p.block<3, 2>(3, 0);
216 
217  // Derivatives of the two entries of xi wrt the basis vectors.
218  const Matrix13 H_xi1_b1 = qn.transpose();
219  const Matrix13 H_xi2_b2 = qn.transpose();
220 
221  // Assemble dxi/dp = dxi/dB * dB/dp.
222  const Matrix12 H_xi1_p = H_xi1_b1 * H_b1_p;
223  const Matrix12 H_xi2_p = H_xi2_b2 * H_b2_p;
224  *H_p << H_xi1_p, H_xi2_p;
225  }
226 
227  if (H_q) {
228  // dxi/dq is given by dxi/dqu * dqu/dq, where qu is the unit vector of q.
229  const Matrix23 H_xi_qu = Bt;
230  *H_q = H_xi_qu * H_qn_q;
231  }
232 
233  return xi;
234 }
235 
236 /* ************************************************************************* */
237 double Unit3::distance(const Unit3& q, OptionalJacobian<1, 2> H) const {
238  Matrix2 H_xi_q;
239  const Vector2 xi = error(q, H ? &H_xi_q : nullptr);
240  const double theta = xi.norm();
241  if (H)
242  *H = (xi.transpose() / theta) * H_xi_q;
243  return theta;
244 }
245 
246 /* ************************************************************************* */
247 Unit3 Unit3::retract(const Vector2& v, OptionalJacobian<2,2> H) const {
248  // Compute the 3D xi_hat vector
249  const Vector3 xi_hat = basis() * v;
250  const double theta = xi_hat.norm();
251  const double c = std::cos(theta);
252 
253  // Treat case of very small v differently.
254  Matrix23 H_from_point;
255  if (theta < std::numeric_limits<double>::epsilon()) {
256  const Unit3 exp_p_xi_hat = Unit3::FromPoint3(c * p_ + xi_hat,
257  H? &H_from_point : nullptr);
258  if (H) { // Jacobian
259  *H = H_from_point *
260  (-p_ * xi_hat.transpose() + Matrix33::Identity()) * basis();
261  }
262  return exp_p_xi_hat;
263  }
264 
265  const double st = std::sin(theta) / theta;
266  const Unit3 exp_p_xi_hat = Unit3::FromPoint3(c * p_ + xi_hat * st,
267  H? &H_from_point : nullptr);
268  if (H) { // Jacobian
269  *H = H_from_point *
270  (p_ * -st * xi_hat.transpose() + st * Matrix33::Identity() +
271  xi_hat * ((c - st) / std::pow(theta, 2)) * xi_hat.transpose()) * basis();
272  }
273  return exp_p_xi_hat;
274 }
275 
276 /* ************************************************************************* */
277 Vector2 Unit3::localCoordinates(const Unit3& other) const {
278  const double x = p_.dot(other.p_);
279  // Crucial quantity here is y = theta/sin(theta) with theta=acos(x)
280  // Now, y = acos(x) / sin(acos(x)) = acos(x)/sqrt(1-x^2)
281  // We treat the special case 1 and -1 below
282  const double x2 = x * x;
283  const double z = 1 - x2;
284  double y;
286  if (x > 0) // first order expansion at x=1
287  y = 1.0 - (x - 1.0) / 3.0;
288  else // cop out
289  return Vector2(M_PI, 0.0);
290  } else {
291  // no special case
292  y = acos(x) / sqrt(z);
293  }
294  return basis().transpose() * y * (other.p_ - x * p_);
295 }
296 /* ************************************************************************* */
297 
298 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
static Point3 CalculateBestAxis(const Point3 &n)
Definition: Unit3.cpp:64
Vector3 p_
The location of the point on the unit sphere.
Definition: Unit3.h:46
GTSAM_EXPORT const Matrix32 & basis(OptionalJacobian< 6, 2 > H=boost::none) const
Definition: Unit3.cpp:76
Scalar * y
Eigen::Vector3d Vector3
Definition: Vector.h:43
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:194
static std::uniform_real_distribution uniform(0.0, 1.0)
ArrayXcf v
Definition: Cwise_arg.cpp:1
static std::mt19937 rng
int n
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
#define M_PI
Definition: main.h:78
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Definition: Half.h:150
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
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
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
std::ostream & operator<<(std::ostream &os, const Unit3 &pair)
Definition: Unit3.cpp:150
static double epsilon
Definition: testRot3.cpp:39
static void normalize(Signature::Row &row)
Definition: Signature.cpp:158
Point3 point(10, 0,-5)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
EIGEN_DEVICE_FUNC const CosReturnType cos() const
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Point3 cross(const Point3 &p, const Point3 &q, OptionalJacobian< 3, 3 > H1, OptionalJacobian< 3, 3 > H2)
cross product
Definition: Point3.cpp:63
RealScalar s
static const Point3 point3(0.08, 0.08, 0.0)
EIGEN_DEVICE_FUNC const Scalar & q
GTSAM_EXPORT Point3 point3(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Point3.
Definition: Unit3.cpp:136
Vector xi
Definition: testPose2.cpp:150
traits
Definition: chartTesting.h:28
EIGEN_DEVICE_FUNC const AcosReturnType acos() const
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
Eigen::Vector2d Vector2
Definition: Vector.h:42
ofstream os("timeSchurFactors.csv")
static double error
Definition: testRot3.cpp:39
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Vector3 Point3
Definition: Point3.h:35
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
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
#define abs(x)
Definition: datatypes.h:17
2D Point


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