src/Geocentric.cpp
Go to the documentation of this file.
1 
11 
12 namespace GeographicLib {
13 
14  using namespace std;
15 
17  : _a(a)
18  , _f(f)
19  , _e2(_f * (2 - _f))
20  , _e2m(Math::sq(1 - _f)) // 1 - _e2
21  , _e2a(abs(_e2))
22  , _e4a(Math::sq(_e2))
23  , _maxrad(2 * _a / numeric_limits<real>::epsilon())
24  {
25  if (!(Math::isfinite(_a) && _a > 0))
26  throw GeographicErr("Equatorial radius is not positive");
27  if (!(Math::isfinite(_f) && _f < 1))
28  throw GeographicErr("Polar semi-axis is not positive");
29  }
30 
32  static const Geocentric wgs84(Constants::WGS84_a(), Constants::WGS84_f());
33  return wgs84;
34  }
35 
37  real& X, real& Y, real& Z,
38  real M[dim2_]) const {
39  real sphi, cphi, slam, clam;
40  Math::sincosd(Math::LatFix(lat), sphi, cphi);
41  Math::sincosd(lon, slam, clam);
42  real n = _a/sqrt(1 - _e2 * Math::sq(sphi));
43  Z = (_e2m * n + h) * sphi;
44  X = (n + h) * cphi;
45  Y = X * slam;
46  X *= clam;
47  if (M)
48  Rotation(sphi, cphi, slam, clam, M);
49  }
50 
52  real& lat, real& lon, real& h,
53  real M[dim2_]) const {
54  real
55  R = Math::hypot(X, Y),
56  slam = R != 0 ? Y / R : 0,
57  clam = R != 0 ? X / R : 1;
58  h = Math::hypot(R, Z); // Distance to center of earth
59  real sphi, cphi;
60  if (h > _maxrad) {
61  // We really far away (> 12 million light years); treat the earth as a
62  // point and h, above, is an acceptable approximation to the height.
63  // This avoids overflow, e.g., in the computation of disc below. It's
64  // possible that h has overflowed to inf; but that's OK.
65  //
66  // Treat the case X, Y finite, but R overflows to +inf by scaling by 2.
67  R = Math::hypot(X/2, Y/2);
68  slam = R != 0 ? (Y/2) / R : 0;
69  clam = R != 0 ? (X/2) / R : 1;
70  real H = Math::hypot(Z/2, R);
71  sphi = (Z/2) / H;
72  cphi = R / H;
73  } else if (_e4a == 0) {
74  // Treat the spherical case. Dealing with underflow in the general case
75  // with _e2 = 0 is difficult. Origin maps to N pole same as with
76  // ellipsoid.
77  real H = Math::hypot(h == 0 ? 1 : Z, R);
78  sphi = (h == 0 ? 1 : Z) / H;
79  cphi = R / H;
80  h -= _a;
81  } else {
82  // Treat prolate spheroids by swapping R and Z here and by switching
83  // the arguments to phi = atan2(...) at the end.
84  real
85  p = Math::sq(R / _a),
86  q = _e2m * Math::sq(Z / _a),
87  r = (p + q - _e4a) / 6;
88  if (_f < 0) swap(p, q);
89  if ( !(_e4a * q == 0 && r <= 0) ) {
90  real
91  // Avoid possible division by zero when r = 0 by multiplying
92  // equations for s and t by r^3 and r, resp.
93  S = _e4a * p * q / 4, // S = r^3 * s
94  r2 = Math::sq(r),
95  r3 = r * r2,
96  disc = S * (2 * r3 + S);
97  real u = r;
98  if (disc >= 0) {
99  real T3 = S + r3;
100  // Pick the sign on the sqrt to maximize abs(T3). This minimizes
101  // loss of precision due to cancellation. The result is unchanged
102  // because of the way the T is used in definition of u.
103  T3 += T3 < 0 ? -sqrt(disc) : sqrt(disc); // T3 = (r * t)^3
104  // N.B. cbrt always returns the real root. cbrt(-8) = -2.
105  real T = Math::cbrt(T3); // T = r * t
106  // T can be zero; but then r2 / T -> 0.
107  u += T + (T != 0 ? r2 / T : 0);
108  } else {
109  // T is complex, but the way u is defined the result is real.
110  real ang = atan2(sqrt(-disc), -(S + r3));
111  // There are three possible cube roots. We choose the root which
112  // avoids cancellation. Note that disc < 0 implies that r < 0.
113  u += 2 * r * cos(ang / 3);
114  }
115  real
116  v = sqrt(Math::sq(u) + _e4a * q), // guaranteed positive
117  // Avoid loss of accuracy when u < 0. Underflow doesn't occur in
118  // e4 * q / (v - u) because u ~ e^4 when q is small and u < 0.
119  uv = u < 0 ? _e4a * q / (v - u) : u + v, // u+v, guaranteed positive
120  // Need to guard against w going negative due to roundoff in uv - q.
121  w = max(real(0), _e2a * (uv - q) / (2 * v)),
122  // Rearrange expression for k to avoid loss of accuracy due to
123  // subtraction. Division by 0 not possible because uv > 0, w >= 0.
124  k = uv / (sqrt(uv + Math::sq(w)) + w),
125  k1 = _f >= 0 ? k : k - _e2,
126  k2 = _f >= 0 ? k + _e2 : k,
127  d = k1 * R / k2,
128  H = Math::hypot(Z/k1, R/k2);
129  sphi = (Z/k1) / H;
130  cphi = (R/k2) / H;
131  h = (1 - _e2m/k1) * Math::hypot(d, Z);
132  } else { // e4 * q == 0 && r <= 0
133  // This leads to k = 0 (oblate, equatorial plane) and k + e^2 = 0
134  // (prolate, rotation axis) and the generation of 0/0 in the general
135  // formulas for phi and h. using the general formula and division by 0
136  // in formula for h. So handle this case by taking the limits:
137  // f > 0: z -> 0, k -> e2 * sqrt(q)/sqrt(e4 - p)
138  // f < 0: R -> 0, k + e2 -> - e2 * sqrt(q)/sqrt(e4 - p)
139  real
140  zz = sqrt((_f >= 0 ? _e4a - p : p) / _e2m),
141  xx = sqrt( _f < 0 ? _e4a - p : p ),
142  H = Math::hypot(zz, xx);
143  sphi = zz / H;
144  cphi = xx / H;
145  if (Z < 0) sphi = -sphi; // for tiny negative Z (not for prolate)
146  h = - _a * (_f >= 0 ? _e2m : 1) * H / _e2a;
147  }
148  }
149  lat = Math::atan2d(sphi, cphi);
150  lon = Math::atan2d(slam, clam);
151  if (M)
152  Rotation(sphi, cphi, slam, clam, M);
153  }
154 
155  void Geocentric::Rotation(real sphi, real cphi, real slam, real clam,
156  real M[dim2_]) {
157  // This rotation matrix is given by the following quaternion operations
158  // qrot(lam, [0,0,1]) * qrot(phi, [0,-1,0]) * [1,1,1,1]/2
159  // or
160  // qrot(pi/2 + lam, [0,0,1]) * qrot(-pi/2 + phi , [-1,0,0])
161  // where
162  // qrot(t,v) = [cos(t/2), sin(t/2)*v[1], sin(t/2)*v[2], sin(t/2)*v[3]]
163 
164  // Local X axis (east) in geocentric coords
165  M[0] = -slam; M[3] = clam; M[6] = 0;
166  // Local Y axis (north) in geocentric coords
167  M[1] = -clam * sphi; M[4] = -slam * sphi; M[7] = cphi;
168  // Local Z axis (up) in geocentric coords
169  M[2] = clam * cphi; M[5] = slam * cphi; M[8] = sphi;
170  }
171 
172 } // namespace GeographicLib
#define max(a, b)
Definition: datatypes.h:20
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:38
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
static const double lat
static T cbrt(T x)
Definition: Math.hpp:345
static bool isfinite(T x)
Definition: Math.hpp:806
ArrayXcf v
Definition: Cwise_arg.cpp:1
int n
static T LatFix(T x)
Definition: Math.hpp:467
Rot2 R(Rot2::fromAngle(0.1))
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Mathematical functions needed by GeographicLib.
Definition: Math.hpp:102
Definition: Half.h:150
static void sincosd(T x, T &sinx, T &cosx)
Definition: Math.hpp:558
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
void IntForward(real lat, real lon, real h, real &X, real &Y, real &Z, real M[dim2_]) const
static double epsilon
Definition: testRot3.cpp:39
Array33i a
Geocentric coordinates
Definition: Geocentric.hpp:67
EIGEN_DEVICE_FUNC const CosReturnType cos() const
#define Z
Definition: icosphere.cpp:21
int EIGEN_BLAS_FUNC() swap(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Definition: level1_impl.h:152
static T hypot(T x, T y)
Definition: Math.hpp:243
static T sq(T x)
Definition: Math.hpp:232
Key S(std::uint64_t j)
static const Geocentric & WGS84()
static T atan2d(T y, T x)
Definition: Math.hpp:691
void IntReverse(real X, real Y, real Z, real &lat, real &lon, real &h, real M[dim2_]) const
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Namespace for GeographicLib.
static const double r2
EIGEN_DEVICE_FUNC const Scalar & q
static const double r3
Header for GeographicLib::Geocentric class.
RowVector3d w
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
Definition: jet.h:556
const double h
static const size_t dim2_
Definition: Geocentric.hpp:77
Exception handling for GeographicLib.
Definition: Constants.hpp:389
static void Rotation(real sphi, real cphi, real slam, real clam, real M[dim2_])
float * p
static const double lon
#define X
Definition: icosphere.cpp:20
#define abs(x)
Definition: datatypes.h:17


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:07