src/Gnomonic.cpp
Go to the documentation of this file.
1 
11 
12 #if defined(_MSC_VER)
13 // Squelch warnings about potentially uninitialized local variables and
14 // constant conditional expressions
15 # pragma warning (disable: 4701 4127)
16 #endif
17 
18 namespace GeographicLib {
19 
20  using namespace std;
21 
23  : eps0_(numeric_limits<real>::epsilon())
24  , eps_(real(0.01) * sqrt(eps0_))
25  , _earth(earth)
26  , _a(_earth.MajorRadius())
27  , _f(_earth.Flattening())
28  {}
29 
31  real& x, real& y, real& azi, real& rk) const {
32  real azi0, m, M, t;
36  t, azi0, azi, m, M, t, t);
37  rk = M;
38  if (M <= 0)
39  x = y = Math::NaN();
40  else {
41  real rho = m/M;
42  Math::sincosd(azi0, x, y);
43  x *= rho; y *= rho;
44  }
45  }
46 
48  real& lat, real& lon, real& azi, real& rk) const {
49  real
50  azi0 = Math::atan2d(x, y),
51  rho = Math::hypot(x, y),
52  s = _a * atan(rho/_a);
53  bool little = rho <= _a;
54  if (!little)
55  rho = 1/rho;
56  GeodesicLine line(_earth.Line(lat0, lon0, azi0,
61  int count = numit_, trip = 0;
62  real lat1, lon1, azi1, M;
63  while (count-- || GEOGRAPHICLIB_PANIC) {
64  real m, t;
65  line.Position(s, lat1, lon1, azi1, m, M, t);
66  if (trip)
67  break;
68  // If little, solve rho(s) = rho with drho(s)/ds = 1/M^2
69  // else solve 1/rho(s) = 1/rho with d(1/rho(s))/ds = -1/m^2
70  real ds = little ? (m/M - rho) * M * M : (rho - M/m) * m * m;
71  s -= ds;
72  // Reversed test to allow escape with NaNs
73  if (!(abs(ds) >= eps_ * _a))
74  ++trip;
75  }
76  if (trip) {
77  lat = lat1; lon = lon1; azi = azi1; rk = M;
78  } else
79  lat = lon = azi = rk = Math::NaN();
80  return;
81  }
82 
83 } // namespace GeographicLib
GeographicLib::Math::NaN
static T NaN()
Definition: Math.hpp:830
GeographicLib::Geodesic::LATITUDE
@ LATITUDE
Definition: Geodesic.hpp:274
s
RealScalar s
Definition: level1_cplx_impl.h:126
atan
const EIGEN_DEVICE_FUNC AtanReturnType atan() const
Definition: ArrayCwiseUnaryOps.h:283
GeographicLib
Namespace for GeographicLib.
Definition: JacobiConformal.hpp:15
GeographicLib::Geodesic::AZIMUTH
@ AZIMUTH
Definition: Geodesic.hpp:286
GeographicLib::GeodesicLine
A geodesic line.
Definition: GeodesicLine.hpp:71
x
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
Definition: gnuplot_common_settings.hh:12
GeographicLib::Gnomonic::Forward
void Forward(real lat0, real lon0, real lat, real lon, real &x, real &y, real &azi, real &rk) const
Definition: src/Gnomonic.cpp:30
GeographicLib::Math::atan2d
static T atan2d(T y, T x)
Definition: Math.hpp:691
GeographicLib::Gnomonic::eps_
real eps_
Definition: Gnomonic.hpp:105
GeographicLib::Math::sincosd
static void sincosd(T x, T &sinx, T &cosx)
Definition: Math.hpp:558
GeographicLib::Gnomonic::_earth
Geodesic _earth
Definition: Gnomonic.hpp:106
GeographicLib::GeodesicLine::Position
Math::real Position(real s12, real &lat2, real &lon2, real &azi2, real &m12, real &M12, real &M21, real &S12) const
Definition: GeodesicLine.hpp:281
GeographicLib::Geodesic::GEODESICSCALE
@ GEODESICSCALE
Definition: Geodesic.hpp:307
GeographicLib::Gnomonic::Gnomonic
Gnomonic(const Geodesic &earth=Geodesic::WGS84())
Definition: src/Gnomonic.cpp:22
epsilon
static double epsilon
Definition: testRot3.cpp:37
GeographicLib::Geodesic::LONGITUDE
@ LONGITUDE
Definition: Geodesic.hpp:279
example::lat0
const double lat0
Definition: testGPSFactor.cpp:41
GEOGRAPHICLIB_PANIC
#define GEOGRAPHICLIB_PANIC
Definition: Math.hpp:87
example::lon0
const double lon0
Definition: testGPSFactor.cpp:41
GeographicLib::Geodesic::Line
GeodesicLine Line(real lat1, real lon1, real azi1, unsigned caps=ALL) const
Definition: src/Geodesic.cpp:118
GeographicLib::Geodesic::GenInverse
real GenInverse(real lat1, real lon1, real lat2, real lon2, unsigned outmask, real &s12, real &salp1, real &calp1, real &salp2, real &calp2, real &m12, real &M12, real &M21, real &S12) const
Definition: src/Geodesic.cpp:159
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
GeographicLib::Gnomonic::numit_
static const int numit_
Definition: Gnomonic.hpp:108
GeographicLib::Gnomonic::Reverse
void Reverse(real lat0, real lon0, real x, real y, real &lat, real &lon, real &azi, real &rk) const
Definition: src/Gnomonic.cpp:47
y
Scalar * y
Definition: level1_cplx_impl.h:124
GeographicLib::Gnomonic::_a
real _a
Definition: Gnomonic.hpp:107
std
Definition: BFloat16.h:88
Gnomonic.hpp
Header for GeographicLib::Gnomonic class.
GeographicLib::Geodesic::REDUCEDLENGTH
@ REDUCEDLENGTH
Definition: Geodesic.hpp:302
abs
#define abs(x)
Definition: datatypes.h:17
lon
static const double lon
Definition: testGeographicLib.cpp:34
align_3::t
Point2 t(10, 10)
GeographicLib::Math::hypot
static T hypot(T x, T y)
Definition: Math.hpp:243
real
Definition: main.h:100
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
GeographicLib::Geodesic
Geodesic calculations
Definition: Geodesic.hpp:172
lat
static const double lat
Definition: testGeographicLib.cpp:34
GeographicLib::Geodesic::DISTANCE_IN
@ DISTANCE_IN
Definition: Geodesic.hpp:297
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:57