coord_system.c
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010 Swift Navigation Inc.
00003  * Contact: Fergus Noble <fergus@swift-nav.com>
00004  *
00005  * This source is subject to the license found in the file 'LICENSE' which must
00006  * be be distributed together with this source. All other rights reserved.
00007  *
00008  * THIS CODE AND INFORMATION IS PROVIDED "AS IS" WITHOUT WARRANTY OF ANY KIND,
00009  * EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE IMPLIED
00010  * WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A PARTICULAR PURPOSE.
00011  */
00012 
00013 #include <math.h>
00014 
00015 #include "constants.h"
00016 #include "linear_algebra.h"
00017 #include "coord_system.h"
00018 
00045 void llhrad2deg(const double llh_rad[3], double llh_deg[3]) {
00046   llh_deg[0] = llh_rad[0]*R2D;
00047   llh_deg[1] = llh_rad[1]*R2D;
00048   llh_deg[2] = llh_rad[2];
00049 }
00050 
00051 
00063 void llhdeg2rad(const double llg_deg[3], double llh_rad[3]) {
00064   llh_rad[0] = llg_deg[0]*D2R;
00065   llh_rad[1] = llg_deg[1]*D2R;
00066   llh_rad[2] = llg_deg[2];
00067 }
00068 
00093 void wgsllh2ecef(const double llh[3], double ecef[3]) {
00094   double d = WGS84_E * sin(llh[0]);
00095   double N = WGS84_A / sqrt(1. - d*d);
00096 
00097   ecef[0] = (N + llh[2]) * cos(llh[0]) * cos(llh[1]);
00098   ecef[1] = (N + llh[2]) * cos(llh[0]) * sin(llh[1]);
00099   ecef[2] = ((1 - WGS84_E*WGS84_E)*N + llh[2]) * sin(llh[0]);
00100 }
00101 
00128 void wgsecef2llh(const double ecef[3], double llh[3]) {
00129   /* Distance from polar axis. */
00130   const double p = sqrt(ecef[0]*ecef[0] + ecef[1]*ecef[1]);
00131 
00132   /* Compute longitude first, this can be done exactly. */
00133   if (p != 0)
00134     llh[1] = atan2(ecef[1], ecef[0]);
00135   else
00136     llh[1] = 0;
00137 
00138   /* If we are close to the pole then convergence is very slow, treat this is a
00139    * special case. */
00140   if (p < WGS84_A*1e-16) {
00141     llh[0] = copysign(M_PI_2, ecef[2]);
00142     llh[2] = fabs(ecef[2]) - WGS84_B;
00143     return;
00144   }
00145 
00146   /* Caluclate some other constants as defined in the Fukushima paper. */
00147   const double P = p / WGS84_A;
00148   const double e_c = sqrt(1. - WGS84_E*WGS84_E);
00149   const double Z = fabs(ecef[2]) * e_c / WGS84_A;
00150 
00151   /* Initial values for S and C correspond to a zero height solution. */
00152   double S = Z;
00153   double C = e_c * P;
00154 
00155   /* Neither S nor C can be negative on the first iteration so
00156    * starting prev = -1 will not cause and early exit. */
00157   double prev_C = -1;
00158   double prev_S = -1;
00159 
00160   double A_n, B_n, D_n, F_n;
00161 
00162   /* Iterate a maximum of 10 times. This should be way more than enough for all
00163    * sane inputs */
00164   for (int i=0; i<10; i++)
00165   {
00166     /* Calculate some intermmediate variables used in the update step based on
00167      * the current state. */
00168     A_n = sqrt(S*S + C*C);
00169     D_n = Z*A_n*A_n*A_n + WGS84_E*WGS84_E*S*S*S;
00170     F_n = P*A_n*A_n*A_n - WGS84_E*WGS84_E*C*C*C;
00171     B_n = 1.5*WGS84_E*S*C*C*(A_n*(P*S - Z*C) - WGS84_E*S*C);
00172 
00173     /* Update step. */
00174     S = D_n*F_n - B_n*S;
00175     C = F_n*F_n - B_n*C;
00176 
00177     /* The original algorithm as presented in the paper by Fukushima has a
00178      * problem with numerical stability. S and C can grow very large or small
00179      * and over or underflow a double. In the paper this is acknowledged and
00180      * the proposed resolution is to non-dimensionalise the equations for S and
00181      * C. However, this does not completely solve the problem. The author caps
00182      * the solution to only a couple of iterations and in this period over or
00183      * underflow is unlikely but as we require a bit more precision and hence
00184      * more iterations so this is still a concern for us.
00185      *
00186      * As the only thing that is important is the ratio T = S/C, my solution is
00187      * to divide both S and C by either S or C. The scaling is chosen such that
00188      * one of S or C is scaled to unity whilst the other is scaled to a value
00189      * less than one. By dividing by the larger of S or C we ensure that we do
00190      * not divide by zero as only one of S or C should ever be zero.
00191      *
00192      * This incurs an extra division each iteration which the author was
00193      * explicityl trying to avoid and it may be that this solution is just
00194      * reverting back to the method of iterating on T directly, perhaps this
00195      * bears more thought?
00196      */
00197 
00198     if (S > C) {
00199       C = C / S;
00200       S = 1;
00201     } else {
00202       S = S / C;
00203       C = 1;
00204     }
00205 
00206     /* Check for convergence and exit early if we have converged. */
00207     if (fabs(S - prev_S) < 1e-16 && fabs(C - prev_C) < 1e-16) {
00208       break;
00209     } else {
00210       prev_S = S;
00211       prev_C = C;
00212     }
00213   }
00214 
00215   A_n = sqrt(S*S + C*C);
00216   llh[0] = copysign(1.0, ecef[2]) * atan(S / (e_c*C));
00217   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);
00218 }
00219 
00228 static void ecef2ned_matrix(const double ref_ecef[3], double M[3][3]) {
00229   double hyp_az, hyp_el;
00230   double sin_el, cos_el, sin_az, cos_az;
00231 
00232   /* Convert reference point to spherical earth centered coordinates. */
00233   hyp_az = sqrt(ref_ecef[0]*ref_ecef[0] + ref_ecef[1]*ref_ecef[1]);
00234   hyp_el = sqrt(hyp_az*hyp_az + ref_ecef[2]*ref_ecef[2]);
00235   sin_el = ref_ecef[2] / hyp_el;
00236   cos_el = hyp_az / hyp_el;
00237   sin_az = ref_ecef[1] / hyp_az;
00238   cos_az = ref_ecef[0] / hyp_az;
00239 
00240   M[0][0] = -sin_el * cos_az;
00241   M[0][1] = -sin_el * sin_az;
00242   M[0][2] = cos_el;
00243   M[1][0] = -sin_az;
00244   M[1][1] = cos_az;
00245   M[1][2] = 0.0;
00246   M[2][0] = -cos_el * cos_az;
00247   M[2][1] = -cos_el * sin_az;
00248   M[2][2] = -sin_el;
00249 }
00250 
00251 
00270 void wgsecef2ned(const double ecef[3], const double ref_ecef[3],
00271                  double ned[3]) {
00272   double M[3][3];
00273 
00274   ecef2ned_matrix(ref_ecef, M);
00275   matrix_multiply(3, 3, 1, (double *)M, ecef, ned);
00276 }
00277 
00292 void wgsecef2ned_d(const double ecef[3], const double ref_ecef[3],
00293                    double ned[3]) {
00294   double tempv[3];
00295   vector_subtract(3, ecef, ref_ecef, tempv);
00296   wgsecef2ned(tempv, ref_ecef, ned);
00297 }
00298 
00299 
00317 void wgsned2ecef(const double ned[3], const double ref_ecef[3],
00318                  double ecef[3]) {
00319   double M[3][3], M_transpose[3][3];
00320   ecef2ned_matrix(ref_ecef, M);
00321   matrix_transpose(3, 3, (double *)M, (double *)M_transpose);
00322   matrix_multiply(3, 3, 1, (double *)M_transpose, ned, ecef);
00323 }
00324 
00338 void wgsned2ecef_d(const double ned[3], const double ref_ecef[3],
00339                    double ecef[3]) {
00340   double tempv[3];
00341   wgsned2ecef(ned, ref_ecef, tempv);
00342   vector_add(3, tempv, ref_ecef, ecef);
00343 }
00344 
00345 
00362 void wgsecef2azel(const double ecef[3], const double ref_ecef[3],
00363                   double* azimuth, double* elevation) {
00364   double ned[3];
00365 
00366   /* Calculate the vector from the reference point in the local North, East,
00367    * Down frame of the reference point. */
00368   wgsecef2ned_d(ecef, ref_ecef, ned);
00369 
00370   *azimuth = atan2(ned[1], ned[0]);
00371   /* atan2 returns angle in range [-pi, pi], usually azimuth is defined in the
00372    * range [0, 2pi]. */
00373   if (*azimuth < 0)
00374     *azimuth += 2*M_PI;
00375 
00376   *elevation = asin(-ned[2]/vector_norm(3, ned));
00377 }
00378 


swiftnav
Author(s):
autogenerated on Sat Jun 8 2019 18:55:32