location_double.cpp 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132
  1. /*
  2. * location_double.cpp
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. /*
  18. this is for double precision functions related to the location structure
  19. */
  20. #define ALLOW_DOUBLE_MATH_FUNCTIONS
  21. #include <AP_HAL/AP_HAL.h>
  22. #include <stdlib.h>
  23. #include "AP_Math.h"
  24. #include "location.h"
  25. /*
  26. these are not currently used. They should be moved to location_double.cpp if we do enable them in the future
  27. */
  28. void wgsllh2ecef(const Vector3d &llh, Vector3d &ecef) {
  29. double d = WGS84_E * sin(llh[0]);
  30. double N = WGS84_A / sqrt(1 - d*d);
  31. ecef[0] = (N + llh[2]) * cos(llh[0]) * cos(llh[1]);
  32. ecef[1] = (N + llh[2]) * cos(llh[0]) * sin(llh[1]);
  33. ecef[2] = ((1 - WGS84_E*WGS84_E)*N + llh[2]) * sin(llh[0]);
  34. }
  35. void wgsecef2llh(const Vector3d &ecef, Vector3d &llh) {
  36. /* Distance from polar axis. */
  37. const double p = sqrt(ecef[0]*ecef[0] + ecef[1]*ecef[1]);
  38. /* Compute longitude first, this can be done exactly. */
  39. if (!is_zero(p))
  40. llh[1] = atan2(ecef[1], ecef[0]);
  41. else
  42. llh[1] = 0;
  43. /* If we are close to the pole then convergence is very slow, treat this is a
  44. * special case. */
  45. if (p < WGS84_A * double(1e-16)) {
  46. llh[0] = copysign(M_PI_2, ecef[2]);
  47. llh[2] = fabs(ecef[2]) - WGS84_B;
  48. return;
  49. }
  50. /* Calculate some other constants as defined in the Fukushima paper. */
  51. const double P = p / WGS84_A;
  52. const double e_c = sqrt(1 - WGS84_E*WGS84_E);
  53. const double Z = fabs(ecef[2]) * e_c / WGS84_A;
  54. /* Initial values for S and C correspond to a zero height solution. */
  55. double S = Z;
  56. double C = e_c * P;
  57. /* Neither S nor C can be negative on the first iteration so
  58. * starting prev = -1 will not cause and early exit. */
  59. double prev_C = -1;
  60. double prev_S = -1;
  61. double A_n, B_n, D_n, F_n;
  62. /* Iterate a maximum of 10 times. This should be way more than enough for all
  63. * sane inputs */
  64. for (int i=0; i<10; i++)
  65. {
  66. /* Calculate some intermmediate variables used in the update step based on
  67. * the current state. */
  68. A_n = sqrt(S*S + C*C);
  69. D_n = Z*A_n*A_n*A_n + WGS84_E*WGS84_E*S*S*S;
  70. F_n = P*A_n*A_n*A_n - WGS84_E*WGS84_E*C*C*C;
  71. B_n = double(1.5) * WGS84_E*S*C*C*(A_n*(P*S - Z*C) - WGS84_E*S*C);
  72. /* Update step. */
  73. S = D_n*F_n - B_n*S;
  74. C = F_n*F_n - B_n*C;
  75. /* The original algorithm as presented in the paper by Fukushima has a
  76. * problem with numerical stability. S and C can grow very large or small
  77. * and over or underflow a double. In the paper this is acknowledged and
  78. * the proposed resolution is to non-dimensionalise the equations for S and
  79. * C. However, this does not completely solve the problem. The author caps
  80. * the solution to only a couple of iterations and in this period over or
  81. * underflow is unlikely but as we require a bit more precision and hence
  82. * more iterations so this is still a concern for us.
  83. *
  84. * As the only thing that is important is the ratio T = S/C, my solution is
  85. * to divide both S and C by either S or C. The scaling is chosen such that
  86. * one of S or C is scaled to unity whilst the other is scaled to a value
  87. * less than one. By dividing by the larger of S or C we ensure that we do
  88. * not divide by zero as only one of S or C should ever be zero.
  89. *
  90. * This incurs an extra division each iteration which the author was
  91. * explicityl trying to avoid and it may be that this solution is just
  92. * reverting back to the method of iterating on T directly, perhaps this
  93. * bears more thought?
  94. */
  95. if (S > C) {
  96. C = C / S;
  97. S = 1;
  98. } else {
  99. S = S / C;
  100. C = 1;
  101. }
  102. /* Check for convergence and exit early if we have converged. */
  103. if (fabs(S - prev_S) < double(1e-16) && fabs(C - prev_C) < double(1e-16)) {
  104. break;
  105. } else {
  106. prev_S = S;
  107. prev_C = C;
  108. }
  109. }
  110. A_n = sqrt(S*S + C*C);
  111. llh[0] = copysign(1.0, ecef[2]) * atan(S / (e_c*C));
  112. llh[2] = (p*e_c*C + fabs(ecef[2])*S - WGS84_A*e_c*A_n) / sqrt(e_c*e_c*C*C + S*S);
  113. }