src/GeodesicLine.cpp
Go to the documentation of this file.
1 
30 
31 namespace GeographicLib {
32 
33  using namespace std;
34 
36  real lat1, real lon1,
37  real azi1, real salp1, real calp1,
38  unsigned caps) {
39  tiny_ = g.tiny_;
40  _lat1 = Math::LatFix(lat1);
41  _lon1 = lon1;
42  _azi1 = azi1;
43  _salp1 = salp1;
44  _calp1 = calp1;
45  _a = g._a;
46  _f = g._f;
47  _b = g._b;
48  _c2 = g._c2;
49  _f1 = g._f1;
50  // Always allow latitude and azimuth and unrolling of longitude
51  _caps = caps | LATITUDE | AZIMUTH | LONG_UNROLL;
52 
53  real cbet1, sbet1;
54  Math::sincosd(Math::AngRound(_lat1), sbet1, cbet1); sbet1 *= _f1;
55  // Ensure cbet1 = +epsilon at poles
56  Math::norm(sbet1, cbet1); cbet1 = max(tiny_, cbet1);
57  _dn1 = sqrt(1 + g._ep2 * Math::sq(sbet1));
58 
59  // Evaluate alp0 from sin(alp1) * cos(bet1) = sin(alp0),
60  _salp0 = _salp1 * cbet1; // alp0 in [0, pi/2 - |bet1|]
61  // Alt: calp0 = hypot(sbet1, calp1 * cbet1). The following
62  // is slightly better (consider the case salp1 = 0).
63  _calp0 = Math::hypot(_calp1, _salp1 * sbet1);
64  // Evaluate sig with tan(bet1) = tan(sig1) * cos(alp1).
65  // sig = 0 is nearest northward crossing of equator.
66  // With bet1 = 0, alp1 = pi/2, we have sig1 = 0 (equatorial line).
67  // With bet1 = pi/2, alp1 = -pi, sig1 = pi/2
68  // With bet1 = -pi/2, alp1 = 0 , sig1 = -pi/2
69  // Evaluate omg1 with tan(omg1) = sin(alp0) * tan(sig1).
70  // With alp0 in (0, pi/2], quadrants for sig and omg coincide.
71  // No atan2(0,0) ambiguity at poles since cbet1 = +epsilon.
72  // With alp0 = 0, omg1 = 0 for alp1 = 0, omg1 = pi for alp1 = pi.
73  _ssig1 = sbet1; _somg1 = _salp0 * sbet1;
74  _csig1 = _comg1 = sbet1 != 0 || _calp1 != 0 ? cbet1 * _calp1 : 1;
75  Math::norm(_ssig1, _csig1); // sig1 in (-pi, pi]
76  // Math::norm(_somg1, _comg1); -- don't need to normalize!
77 
78  _k2 = Math::sq(_calp0) * g._ep2;
79  real eps = _k2 / (2 * (1 + sqrt(1 + _k2)) + _k2);
80 
81  if (_caps & CAP_C1) {
82  _A1m1 = Geodesic::A1m1f(eps);
83  Geodesic::C1f(eps, _C1a);
84  _B11 = Geodesic::SinCosSeries(true, _ssig1, _csig1, _C1a, nC1_);
85  real s = sin(_B11), c = cos(_B11);
86  // tau1 = sig1 + B11
87  _stau1 = _ssig1 * c + _csig1 * s;
88  _ctau1 = _csig1 * c - _ssig1 * s;
89  // Not necessary because C1pa reverts C1a
90  // _B11 = -SinCosSeries(true, _stau1, _ctau1, _C1pa, nC1p_);
91  }
92 
93  if (_caps & CAP_C1p)
94  Geodesic::C1pf(eps, _C1pa);
95 
96  if (_caps & CAP_C2) {
97  _A2m1 = Geodesic::A2m1f(eps);
98  Geodesic::C2f(eps, _C2a);
99  _B21 = Geodesic::SinCosSeries(true, _ssig1, _csig1, _C2a, nC2_);
100  }
101 
102  if (_caps & CAP_C3) {
103  g.C3f(eps, _C3a);
104  _A3c = -_f * _salp0 * g.A3f(eps);
105  _B31 = Geodesic::SinCosSeries(true, _ssig1, _csig1, _C3a, nC3_-1);
106  }
107 
108  if (_caps & CAP_C4) {
109  g.C4f(eps, _C4a);
110  // Multiplier = a^2 * e^2 * cos(alpha0) * sin(alpha0)
111  _A4 = Math::sq(_a) * _calp0 * _salp0 * g._e2;
112  _B41 = Geodesic::SinCosSeries(false, _ssig1, _csig1, _C4a, nC4_);
113  }
114 
115  _a13 = _s13 = Math::NaN();
116  }
117 
119  real lat1, real lon1, real azi1,
120  unsigned caps) {
121  azi1 = Math::AngNormalize(azi1);
122  real salp1, calp1;
123  // Guard against underflow in salp0. Also -0 is converted to +0.
124  Math::sincosd(Math::AngRound(azi1), salp1, calp1);
125  LineInit(g, lat1, lon1, azi1, salp1, calp1, caps);
126  }
127 
129  real lat1, real lon1,
130  real azi1, real salp1, real calp1,
131  unsigned caps, bool arcmode, real s13_a13) {
132  LineInit(g, lat1, lon1, azi1, salp1, calp1, caps);
133  GenSetDistance(arcmode, s13_a13);
134  }
135 
137  unsigned outmask,
138  real& lat2, real& lon2, real& azi2,
139  real& s12, real& m12,
140  real& M12, real& M21,
141  real& S12) const {
142  outmask &= _caps & OUT_MASK;
143  if (!( Init() && (arcmode || (_caps & (OUT_MASK & DISTANCE_IN))) ))
144  // Uninitialized or impossible distance calculation requested
145  return Math::NaN();
146 
147  // Avoid warning about uninitialized B12.
148  real sig12, ssig12, csig12, B12 = 0, AB1 = 0;
149  if (arcmode) {
150  // Interpret s12_a12 as spherical arc length
151  sig12 = s12_a12 * Math::degree();
152  Math::sincosd(s12_a12, ssig12, csig12);
153  } else {
154  // Interpret s12_a12 as distance
155  real
156  tau12 = s12_a12 / (_b * (1 + _A1m1)),
157  s = sin(tau12),
158  c = cos(tau12);
159  // tau2 = tau1 + tau12
160  B12 = - Geodesic::SinCosSeries(true,
161  _stau1 * c + _ctau1 * s,
162  _ctau1 * c - _stau1 * s,
163  _C1pa, nC1p_);
164  sig12 = tau12 - (B12 - _B11);
165  ssig12 = sin(sig12); csig12 = cos(sig12);
166  if (abs(_f) > 0.01) {
167  // Reverted distance series is inaccurate for |f| > 1/100, so correct
168  // sig12 with 1 Newton iteration. The following table shows the
169  // approximate maximum error for a = WGS_a() and various f relative to
170  // GeodesicExact.
171  // erri = the error in the inverse solution (nm)
172  // errd = the error in the direct solution (series only) (nm)
173  // errda = the error in the direct solution
174  // (series + 1 Newton) (nm)
175  //
176  // f erri errd errda
177  // -1/5 12e6 1.2e9 69e6
178  // -1/10 123e3 12e6 765e3
179  // -1/20 1110 108e3 7155
180  // -1/50 18.63 200.9 27.12
181  // -1/100 18.63 23.78 23.37
182  // -1/150 18.63 21.05 20.26
183  // 1/150 22.35 24.73 25.83
184  // 1/100 22.35 25.03 25.31
185  // 1/50 29.80 231.9 30.44
186  // 1/20 5376 146e3 10e3
187  // 1/10 829e3 22e6 1.5e6
188  // 1/5 157e6 3.8e9 280e6
189  real
190  ssig2 = _ssig1 * csig12 + _csig1 * ssig12,
191  csig2 = _csig1 * csig12 - _ssig1 * ssig12;
192  B12 = Geodesic::SinCosSeries(true, ssig2, csig2, _C1a, nC1_);
193  real serr = (1 + _A1m1) * (sig12 + (B12 - _B11)) - s12_a12 / _b;
194  sig12 = sig12 - serr / sqrt(1 + _k2 * Math::sq(ssig2));
195  ssig12 = sin(sig12); csig12 = cos(sig12);
196  // Update B12 below
197  }
198  }
199 
200  real ssig2, csig2, sbet2, cbet2, salp2, calp2;
201  // sig2 = sig1 + sig12
202  ssig2 = _ssig1 * csig12 + _csig1 * ssig12;
203  csig2 = _csig1 * csig12 - _ssig1 * ssig12;
204  real dn2 = sqrt(1 + _k2 * Math::sq(ssig2));
205  if (outmask & (DISTANCE | REDUCEDLENGTH | GEODESICSCALE)) {
206  if (arcmode || abs(_f) > 0.01)
207  B12 = Geodesic::SinCosSeries(true, ssig2, csig2, _C1a, nC1_);
208  AB1 = (1 + _A1m1) * (B12 - _B11);
209  }
210  // sin(bet2) = cos(alp0) * sin(sig2)
211  sbet2 = _calp0 * ssig2;
212  // Alt: cbet2 = hypot(csig2, salp0 * ssig2);
213  cbet2 = Math::hypot(_salp0, _calp0 * csig2);
214  if (cbet2 == 0)
215  // I.e., salp0 = 0, csig2 = 0. Break the degeneracy in this case
216  cbet2 = csig2 = tiny_;
217  // tan(alp0) = cos(sig2)*tan(alp2)
218  salp2 = _salp0; calp2 = _calp0 * csig2; // No need to normalize
219 
220  if (outmask & DISTANCE)
221  s12 = arcmode ? _b * ((1 + _A1m1) * sig12 + AB1) : s12_a12;
222 
223  if (outmask & LONGITUDE) {
224  // tan(omg2) = sin(alp0) * tan(sig2)
225  real somg2 = _salp0 * ssig2, comg2 = csig2, // No need to normalize
226  E = Math::copysign(real(1), _salp0); // east-going?
227  // omg12 = omg2 - omg1
228  real omg12 = outmask & LONG_UNROLL
229  ? E * (sig12
230  - (atan2( ssig2, csig2) - atan2( _ssig1, _csig1))
231  + (atan2(E * somg2, comg2) - atan2(E * _somg1, _comg1)))
232  : atan2(somg2 * _comg1 - comg2 * _somg1,
233  comg2 * _comg1 + somg2 * _somg1);
234  real lam12 = omg12 + _A3c *
235  ( sig12 + (Geodesic::SinCosSeries(true, ssig2, csig2, _C3a, nC3_-1)
236  - _B31));
237  real lon12 = lam12 / Math::degree();
238  lon2 = outmask & LONG_UNROLL ? _lon1 + lon12 :
240  Math::AngNormalize(lon12));
241  }
242 
243  if (outmask & LATITUDE)
244  lat2 = Math::atan2d(sbet2, _f1 * cbet2);
245 
246  if (outmask & AZIMUTH)
247  azi2 = Math::atan2d(salp2, calp2);
248 
249  if (outmask & (REDUCEDLENGTH | GEODESICSCALE)) {
250  real
251  B22 = Geodesic::SinCosSeries(true, ssig2, csig2, _C2a, nC2_),
252  AB2 = (1 + _A2m1) * (B22 - _B21),
253  J12 = (_A1m1 - _A2m1) * sig12 + (AB1 - AB2);
254  if (outmask & REDUCEDLENGTH)
255  // Add parens around (_csig1 * ssig2) and (_ssig1 * csig2) to ensure
256  // accurate cancellation in the case of coincident points.
257  m12 = _b * ((dn2 * (_csig1 * ssig2) - _dn1 * (_ssig1 * csig2))
258  - _csig1 * csig2 * J12);
259  if (outmask & GEODESICSCALE) {
260  real t = _k2 * (ssig2 - _ssig1) * (ssig2 + _ssig1) / (_dn1 + dn2);
261  M12 = csig12 + (t * ssig2 - csig2 * J12) * _ssig1 / _dn1;
262  M21 = csig12 - (t * _ssig1 - _csig1 * J12) * ssig2 / dn2;
263  }
264  }
265 
266  if (outmask & AREA) {
267  real
268  B42 = Geodesic::SinCosSeries(false, ssig2, csig2, _C4a, nC4_);
269  real salp12, calp12;
270  if (_calp0 == 0 || _salp0 == 0) {
271  // alp12 = alp2 - alp1, used in atan2 so no need to normalize
272  salp12 = salp2 * _calp1 - calp2 * _salp1;
273  calp12 = calp2 * _calp1 + salp2 * _salp1;
274  // We used to include here some patch up code that purported to deal
275  // with nearly meridional geodesics properly. However, this turned out
276  // to be wrong once _salp1 = -0 was allowed (via
277  // Geodesic::InverseLine). In fact, the calculation of {s,c}alp12
278  // was already correct (following the IEEE rules for handling signed
279  // zeros). So the patch up code was unnecessary (as well as
280  // dangerous).
281  } else {
282  // tan(alp) = tan(alp0) * sec(sig)
283  // tan(alp2-alp1) = (tan(alp2) -tan(alp1)) / (tan(alp2)*tan(alp1)+1)
284  // = calp0 * salp0 * (csig1-csig2) / (salp0^2 + calp0^2 * csig1*csig2)
285  // If csig12 > 0, write
286  // csig1 - csig2 = ssig12 * (csig1 * ssig12 / (1 + csig12) + ssig1)
287  // else
288  // csig1 - csig2 = csig1 * (1 - csig12) + ssig12 * ssig1
289  // No need to normalize
290  salp12 = _calp0 * _salp0 *
291  (csig12 <= 0 ? _csig1 * (1 - csig12) + ssig12 * _ssig1 :
292  ssig12 * (_csig1 * ssig12 / (1 + csig12) + _ssig1));
293  calp12 = Math::sq(_salp0) + Math::sq(_calp0) * _csig1 * csig2;
294  }
295  S12 = _c2 * atan2(salp12, calp12) + _A4 * (B42 - _B41);
296  }
297 
298  return arcmode ? s12_a12 : sig12 / Math::degree();
299  }
300 
302  _s13 = s13;
303  real t;
304  // This will set _a13 to NaN if the GeodesicLine doesn't have the
305  // DISTANCE_IN capability.
306  _a13 = GenPosition(false, _s13, 0u, t, t, t, t, t, t, t, t);
307  }
308 
310  _a13 = a13;
311  // In case the GeodesicLine doesn't have the DISTANCE capability.
312  _s13 = Math::NaN();
313  real t;
314  GenPosition(true, _a13, DISTANCE, t, t, t, _s13, t, t, t, t);
315  }
316 
317  void GeodesicLine::GenSetDistance(bool arcmode, real s13_a13) {
318  arcmode ? SetArc(s13_a13) : SetDistance(s13_a13);
319  }
320 
321 } // namespace GeographicLib
static T AngNormalize(T x)
Definition: Math.hpp:440
static T NaN()
Definition: Math.hpp:830
#define max(a, b)
Definition: datatypes.h:20
Header for GeographicLib::GeodesicLine class.
Key E(std::uint64_t j)
float real
Definition: datatypes.h:10
static void C2f(real eps, real c[])
static T LatFix(T x)
Definition: Math.hpp:467
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
void LineInit(const Geodesic &g, real lat1, real lon1, real azi1, real salp1, real calp1, unsigned caps)
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Definition: Half.h:150
static void sincosd(T x, T &sinx, T &cosx)
Definition: Math.hpp:558
void C4f(real k2, real c[]) const
static void norm(T &x, T &y)
Definition: Math.hpp:384
real A3f(real eps) const
void g(const string &key, int i)
Definition: testBTree.cpp:43
EIGEN_DEVICE_FUNC const CosReturnType cos() const
void GenSetDistance(bool arcmode, real s13_a13)
static real A1m1f(real eps)
static T hypot(T x, T y)
Definition: Math.hpp:243
static void C1f(real eps, real c[])
static T sq(T x)
Definition: Math.hpp:232
Math::real GenPosition(bool arcmode, real s12_a12, unsigned outmask, real &lat2, real &lon2, real &azi2, real &s12, real &m12, real &M12, real &M21, real &S12) const
static T atan2d(T y, T x)
Definition: Math.hpp:691
static real SinCosSeries(bool sinp, real sinx, real cosx, const real c[], int n)
Namespace for GeographicLib.
RealScalar s
static T degree()
Definition: Math.hpp:216
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
Definition: jet.h:556
static T copysign(T x, T y)
Definition: Math.hpp:751
static real A2m1f(real eps)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
void C3f(real eps, real c[]) const
#define abs(x)
Definition: datatypes.h:17
Geodesic calculations
Definition: Geodesic.hpp:172
static void C1pf(real eps, real c[])
static T AngRound(T x)
Definition: Math.hpp:535
Point2 t(10, 10)


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