14 #if !defined(GEOGRAPHICLIB_MATH_HPP) 15 #define GEOGRAPHICLIB_MATH_HPP 1 20 #if !defined(GEOGRAPHICLIB_CXX11_MATH) 28 # if defined(__GNUC__) && __cplusplus >= 201103 && \ 29 !(defined(__ANDROID__) || defined(ANDROID) || defined(__CYGWIN__)) 30 # define GEOGRAPHICLIB_CXX11_MATH 1 32 # elif defined(_MSC_VER) && _MSC_VER >= 1800 33 # define GEOGRAPHICLIB_CXX11_MATH 1 35 # define GEOGRAPHICLIB_CXX11_MATH 0 39 #if !defined(GEOGRAPHICLIB_WORDS_BIGENDIAN) 40 # define GEOGRAPHICLIB_WORDS_BIGENDIAN 0 43 #if !defined(GEOGRAPHICLIB_HAVE_LONG_DOUBLE) 44 # define GEOGRAPHICLIB_HAVE_LONG_DOUBLE 0 47 #if !defined(GEOGRAPHICLIB_PRECISION) 57 # define GEOGRAPHICLIB_PRECISION 2 64 #if GEOGRAPHICLIB_PRECISION == 4 65 #include <boost/version.hpp> 66 #if BOOST_VERSION >= 105600 67 #include <boost/cstdfloat.hpp> 69 #include <boost/multiprecision/float128.hpp> 70 #include <boost/math/special_functions.hpp> 71 __float128 fmaq(__float128, __float128, __float128);
72 #elif GEOGRAPHICLIB_PRECISION == 5 76 #if GEOGRAPHICLIB_PRECISION > 3 78 #define GEOGRAPHICLIB_VOLATILE 81 #define GEOGRAPHICLIB_PANIC \ 82 (throw GeographicLib::GeographicErr("Convergence failure"), false) 84 #define GEOGRAPHICLIB_VOLATILE volatile 87 #define GEOGRAPHICLIB_PANIC false 107 "Bad value of precision");
112 #if GEOGRAPHICLIB_HAVE_LONG_DOUBLE 122 #if GEOGRAPHICLIB_PRECISION == 2 130 #elif GEOGRAPHICLIB_PRECISION == 1 132 #elif GEOGRAPHICLIB_PRECISION == 3 133 typedef extended
real;
134 #elif GEOGRAPHICLIB_PRECISION == 4 135 typedef boost::multiprecision::float128
real;
136 #elif GEOGRAPHICLIB_PRECISION == 5 137 typedef mpfr::mpreal
real;
146 #if GEOGRAPHICLIB_PRECISION != 5 147 return std::numeric_limits<real>::digits;
149 return std::numeric_limits<real>::digits();
164 #if GEOGRAPHICLIB_PRECISION != 5 167 mpfr::mpreal::set_default_prec(ndigits >= 2 ? ndigits : 2);
176 #if GEOGRAPHICLIB_PRECISION != 5 177 return std::numeric_limits<real>::digits10;
179 return std::numeric_limits<real>::digits10();
189 digits10() > std::numeric_limits<double>::digits10 ?
190 digits10() - std::numeric_limits<double>::digits10 : 0;
202 template<
typename T>
static T pi() {
204 static const T pi =
atan2(
T(0),
T(-1));
210 static real
pi() {
return pi<real>(); }
217 static const T degree = pi<T>() / 180;
223 static real
degree() {
return degree<real>(); }
232 template<
typename T>
static T sq(
T x)
244 #if GEOGRAPHICLIB_CXX11_MATH 245 using std::hypot;
return hypot(x, y);
251 return x *
sqrt(1 + y * y);
266 #if GEOGRAPHICLIB_CXX11_MATH 277 return abs(x) > 1 ?
z : (
z == 0 ?
x : x *
z /
log(y));
289 #if GEOGRAPHICLIB_CXX11_MATH 300 return z == 0 ?
x : x *
log(y) /
z;
312 #if GEOGRAPHICLIB_CXX11_MATH 313 using std::asinh;
return asinh(x);
316 y =
log1p(y * (1 + y/(hypot(
T(1), y) + 1)));
317 return x < 0 ? -
y :
y;
329 #if GEOGRAPHICLIB_CXX11_MATH 330 using std::atanh;
return atanh(x);
333 y =
log1p(2 * y/(1 - y))/2;
334 return x < 0 ? -
y :
y;
346 #if GEOGRAPHICLIB_CXX11_MATH 347 using std::cbrt;
return cbrt(x);
351 return x < 0 ? -
y :
y;
370 #if GEOGRAPHICLIB_CXX11_MATH 371 using std::fma;
return fma(x, y, z);
385 {
T h = hypot(x, y); x /=
h; y /=
h; }
429 {
T y = N < 0 ? 0 : *p++;
while (--N >= 0) y = y * x + *p++;
return y; }
441 #if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION != 4 442 using std::remainder;
443 x = remainder(x,
T(360));
return x != -180 ?
x : 180;
447 #if defined(_MSC_VER) && _MSC_VER < 1900 455 return y <= -180 ? y + 360 : (y <= 180 ?
y : y - 360);
468 {
using std::abs;
return abs(x) > 90 ? NaN<T>() : x; }
487 #if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION != 4 488 using std::remainder;
489 T t,
d = AngNormalize(sum(remainder(-x,
T(360)),
490 remainder( y,
T(360)), t));
492 T t, d = AngNormalize(sum(AngNormalize(-x), AngNormalize(y), t));
500 return sum(d == 180 && t > 0 ? -180 : d, t, e);
518 {
T e;
return AngDiff(x, y, e); }
537 static const T z = 1/
T(16);
538 if (x == 0)
return 0;
541 y = y < z ? z - (z -
y) : y;
542 return x < 0 ? -
y :
y;
563 #if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION <= 3 && \ 572 r = remquo(x,
T(90), &q);
583 #if defined(_MSC_VER) && _MSC_VER < 1900 592 switch (
unsigned(q) & 3
U) {
593 case 0
U: sinx =
s; cosx =
c;
break;
594 case 1
U: sinx =
c; cosx = -
s;
break;
595 case 2
U: sinx = -
s; cosx = -
c;
break;
596 default: sinx = -
c; cosx =
s;
break;
599 if (x != 0) { sinx +=
T(0); cosx +=
T(0); }
613 #if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION <= 3 && \ 616 r = remquo(x,
T(90), &q);
625 unsigned p = unsigned(q);
628 if (x != 0) r +=
T(0);
643 #if GEOGRAPHICLIB_CXX11_MATH && GEOGRAPHICLIB_PRECISION <= 3 && \ 646 r = remquo(x,
T(90), &q);
655 unsigned p = unsigned(q + 1);
675 return c != 0 ? s /
c : (s < 0 ? -overflow : overflow);
699 if (x < 0) { x = -
x; ++
q; }
709 case 1: ang = (y >= 0 ? 180 : -180) - ang;
break;
710 case 2: ang = 90 - ang;
break;
711 case 3: ang = -90 + ang;
break;
724 {
return atan2d(x,
T(1)); }
738 template<
typename T>
static T eatanhe(
T x,
T es);
752 #if GEOGRAPHICLIB_CXX11_MATH 753 using std::copysign;
return copysign(x, y);
757 return abs(x) * (y < 0 || (y == 0 && 1/y < 0) ? -1 : 1);
778 template<
typename T>
static T taupf(
T tau,
T es);
797 template<
typename T>
static T tauf(
T taup,
T es);
807 #if GEOGRAPHICLIB_CXX11_MATH 811 #if defined(_MSC_VER) 830 template<
typename T>
static T NaN() {
831 #if defined(_MSC_VER) 832 return std::numeric_limits<T>::has_quiet_NaN ?
833 std::numeric_limits<T>::quiet_NaN() :
836 return std::numeric_limits<T>::has_quiet_NaN ?
837 std::numeric_limits<T>::quiet_NaN() :
844 static real
NaN() {
return NaN<real>(); }
853 template<
typename T>
static bool isnan(
T x) {
854 #if GEOGRAPHICLIB_CXX11_MATH 868 #if defined(_MSC_VER) 869 return std::numeric_limits<T>::has_infinity ?
870 std::numeric_limits<T>::infinity() :
873 return std::numeric_limits<T>::has_infinity ?
874 std::numeric_limits<T>::infinity() :
881 static real
infinity() {
return infinity<real>(); }
890 template<
typename T>
static T swab(
T x) {
893 unsigned char c[
sizeof(
T)];
896 for (
int i =
sizeof(
T)/2;
i--; )
901 #if GEOGRAPHICLIB_PRECISION == 4 902 typedef boost::math::policies::policy
903 < boost::math::policies::domain_error
904 <boost::math::policies::errno_on_error>,
905 boost::math::policies::pole_error
906 <boost::math::policies::errno_on_error>,
907 boost::math::policies::overflow_error
908 <boost::math::policies::errno_on_error>,
909 boost::math::policies::evaluation_error
910 <boost::math::policies::errno_on_error> >
911 boost_special_functions_policy;
913 static real hypot(real x, real
y)
914 {
return boost::math::hypot(x, y, boost_special_functions_policy()); }
916 static real
expm1(real x)
919 static real
log1p(real x)
922 static real asinh(real x)
923 {
return boost::math::asinh(x, boost_special_functions_policy()); }
925 static real atanh(real x)
926 {
return boost::math::atanh(x, boost_special_functions_policy()); }
928 static real cbrt(real x)
929 {
return boost::math::cbrt(x, boost_special_functions_policy()); }
931 static real fma(real x, real y, real
z)
932 {
return fmaq(__float128(x), __float128(y), __float128(z)); }
934 static real copysign(real x, real y)
935 {
return boost::math::copysign(x, y); }
945 #endif // GEOGRAPHICLIB_MATH_HPP static T AngNormalize(T x)
EIGEN_DEVICE_FUNC const Log1pReturnType log1p() const
static T sum(T u, T v, T &t)
static int set_digits(int ndigits)
#define GEOGRAPHICLIB_EXPORT
Jet< T, N > cos(const Jet< T, N > &f)
#define GEOGRAPHICLIB_WORDS_BIGENDIAN
static bool isfinite(T x)
Jet< T, N > sin(const Jet< T, N > &f)
Mathematical functions needed by GeographicLib.
static void sincosd(T x, T &sinx, T &cosx)
static T AngDiff(T x, T y, T &e)
static void norm(T &x, T &y)
#define GEOGRAPHICLIB_PRECISION
EIGEN_DEVICE_FUNC const LogReturnType log() const
#define GEOGRAPHICLIB_VOLATILE
static int extra_digits()
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
EIGEN_DEVICE_FUNC const FloorReturnType floor() const
EIGEN_DEVICE_FUNC const Expm1ReturnType expm1() const
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 fmod(const bfloat16 &a, const bfloat16 &b)
Array< int, Dynamic, 1 > v
static T atan2d(T y, T x)
Eigen::Triplet< double > T
static T polyval(int N, const T p[], T x)
Namespace for GeographicLib.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
static T AngDiff(T x, T y)
void swap(GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &a, GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &b)
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
static T copysign(T x, T y)
Header for GeographicLib::Constants class.
EigenSolver< MatrixXf > es
static T fma(T x, T y, T z)
Jet< T, N > sqrt(const Jet< T, N > &f)
Jet< T, N > pow(const Jet< T, N > &f, double g)
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