21 , _c2(_ell.Area() / 720)
24 #if GEOGRAPHICLIB_RHUMBAREA_ORDER == 4 25 static const real coeff[] = {
27 691, 7860, -20160, 18900, 0, 56700,
29 1772, -5340, 6930, -4725, 14175,
31 -1747, 1590, -630, 4725,
37 #elif GEOGRAPHICLIB_RHUMBAREA_ORDER == 5 38 static const real coeff[] = {
40 -79036, 22803, 259380, -665280, 623700, 0, 1871100,
42 41662, 58476, -176220, 228690, -155925, 467775,
44 18118, -57651, 52470, -20790, 155925,
46 -23011, 17160, -5115, 51975,
52 #elif GEOGRAPHICLIB_RHUMBAREA_ORDER == 6 53 static const real coeff[] = {
55 128346268, -107884140, 31126095, 354053700, -908107200, 851350500, 0,
58 -114456994, 56868630, 79819740, -240540300, 312161850, -212837625,
61 51304574, 24731070, -78693615, 71621550, -28378350, 212837625,
63 1554472, -6282003, 4684680, -1396395, 14189175,
65 -4913956, 3205800, -791505, 8108100,
67 1092376, -234468, 2027025,
71 #elif GEOGRAPHICLIB_RHUMBAREA_ORDER == 7 72 static const real coeff[] = {
74 -317195588, 385038804, -323652420, 93378285, 1062161100, -2724321600LL,
75 2554051500LL, 0, 7662154500LL,
77 258618446, -343370982, 170605890, 239459220, -721620900, 936485550,
78 -638512875, 1915538625,
80 -248174686, 153913722, 74193210, -236080845, 214864650, -85135050,
83 114450437, 23317080, -94230045, 70270200, -20945925, 212837625,
85 15445736, -103193076, 67321800, -16621605, 170270100,
87 -27766753, 16385640, -3517020, 30405375,
89 4892722, -939228, 6081075,
93 #elif GEOGRAPHICLIB_RHUMBAREA_ORDER == 8 94 static const real coeff[] = {
96 71374704821LL, -161769749880LL, 196369790040LL, -165062734200LL,
97 47622925350LL, 541702161000LL, -1389404016000LL, 1302566265000LL, 0,
100 -13691187484LL, 65947703730LL, -87559600410LL, 43504501950LL,
101 61062101100LL, -184013329500LL, 238803815250LL, -162820783125LL,
104 30802104839LL, -63284544930LL, 39247999110LL, 18919268550LL,
105 -60200615475LL, 54790485750LL, -21709437750LL, 162820783125LL,
107 -8934064508LL, 5836972287LL, 1189171080, -4805732295LL, 3583780200LL,
108 -1068242175, 10854718875LL,
110 50072287748LL, 3938662680LL, -26314234380LL, 17167059000LL,
111 -4238509275LL, 43418875500LL,
113 359094172, -9912730821LL, 5849673480LL, -1255576140, 10854718875LL,
115 -16053944387LL, 8733508770LL, -1676521980, 10854718875LL,
117 930092876, -162639357, 723647925,
119 -673429061, 1929727800,
122 #error "Bad value for GEOGRAPHICLIB_RHUMBAREA_ORDER" 124 GEOGRAPHICLIB_STATIC_ASSERT(
sizeof(coeff) /
sizeof(
real) ==
126 "Coefficient array size mismatch for Rhumb");
174 {
Line(lat1, lon1, azi12).
GenPosition(s12, outmask, lat2, lon2, S12); }
180 return d != 0 ? (ei.
E(x) - ei.
E(y)) / d : 1;
199 t = d * Dt, Dsz = 2 * Dt / (1 +
t*
t),
200 sz = d * Dsz, cz = (1 -
t) * (1 +
t) / (1 +
t*
t);
201 return ((sz != 0 ? ei.
E(sz, cz, ei.
Delta(sz, cz)) / sz : 1)
202 - ei.
k2() * sx * sy) * Dsz;
258 sp =
sin(p), sd = d != 0 ?
sin(d)/
d : 1,
259 m = 2 * cp * cd,
s = sp * sd;
261 const real a[4] = {
m, -s * d *
d, -4 *
s,
m};
262 real ba[4] = {0, 0, 0, 0};
263 real bb[4] = {0, 0, 0, 0};
266 if (n > 0) b1[0] = b1[3] = c[
n];
267 for (
int j = n - 1;
j > 0; --
j) {
270 b1[0] = a[0] * b2[0] + a[1] * b2[2] - b1[0] + c[
j];
271 b1[1] = a[0] * b2[1] + a[1] * b2[3] - b1[1];
272 b1[2] = a[2] * b2[0] + a[3] * b2[2] - b1[2];
273 b1[3] = a[2] * b2[1] + a[3] * b2[3] - b1[3] + c[
j];
280 real f11 = cd * sp, f12 = 2 * sd * cp;
282 s = b1[2] * f11 + b1[3] * f12;
285 real f11 = cd * cp, f12 = - 2 * sd * sp;
287 s = - b2[2] + b1[2] * f11 + b1[3] * f12;
335 , _lat1(
Math::LatFix(lat1))
337 , _azi12(
Math::AngNormalize(azi12))
352 real psi2, lat2x, lon2x;
353 if (
abs(mu2) <= 90) {
359 psi2 =
_psi1 + psi12;
380 if (outmask &
LATITUDE) lat2 = lat2x;
static T AngNormalize(T x)
static real Dasinh(real x, real y)
real Deatanhe(real x, real y) const
RhumbLine Line(real lat1, real lon1, real azi12) const
static real Dgd(real x, real y)
Jet< T, N > cos(const Jet< T, N > &f)
static real SinCosSeries(bool sinp, real x, real y, const real c[], int n)
static real Dtan(real x, real y)
real DRectifyingToIsometric(real mux, real muy) const
Math::real IsometricLatitude(real phi) const
static real Dcosh(real x, real y)
const Math::real * RectifyingToConformalCoeffs() const
Math::real InverseRectifyingLatitude(real mu) const
Math::real CircleRadius(real phi) const
Jet< T, N > sin(const Jet< T, N > &f)
Mathematical functions needed by GeographicLib.
static real Dlog(real x, real y)
Rhumb(real a, real f, bool exact=true)
static T AngDiff(T x, T y, T &e)
Header for GeographicLib::Rhumb and GeographicLib::RhumbLine classes.
Elliptic integrals and functions.
Math::real QuarterMeridian() const
static real Dsin(real x, real y)
void GenDirect(real lat1, real lon1, real azi12, bool, real s12, unsigned outmask, real &lat2, real &lon2, real &, real &, real &, real &, real &, real &S12) const
real MeanSinXi(real psi1, real psi2) const
EIGEN_DEVICE_FUNC const AtanReturnType atan() const
RhumbLine(const Rhumb &rh, real lat1, real lon1, real azi12, bool exact)
static const Line3 l(Rot3(), 1, 1)
static const Rhumb & WGS84()
static T atan2d(T y, T x)
static T polyval(int N, const T p[], T x)
static real Datan(real x, real y)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Namespace for GeographicLib.
real DRectifying(real latx, real laty) const
real DConformalToRectifying(real chix, real chiy) const
Math::real InverseIsometricLatitude(real psi) const
Math::real RectifyingLatitude(real phi) const
void swap(GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &a, GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &b)
static real Dgdinv(real x, real y)
static const int tm_maxord
Math::real Delta(real sn, real cn) const
Solve of the direct and inverse rhumb problems.
void GenInverse(real lat1, real lon1, real lat2, real lon2, unsigned outmask, real &s12, real &azi12, real &, real &, real &, real &, real &S12) const
real DIsometricToRectifying(real psix, real psiy) const
Find a sequence of points on a single rhumb line.
real DE(real x, real y) const
EIGEN_DEVICE_FUNC const CoshReturnType cosh() const
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
real DRectifyingToConformal(real mux, real muy) const
void GenPosition(real s12, unsigned outmask, real &lat2, real &lon2, real &S12) const
const Math::real * ConformalToRectifyingCoeffs() const
real DIsometric(real latx, real laty) const
static T taupf(T tau, T es)