GeodeticCoords.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 /*
00029  * The methods in this file were modified from the originals of the MRPT toolkit (see notice below):
00030  * https://github.com/MRPT/mrpt/blob/master/libs/topography/src/conversions.cpp
00031  */
00032 
00033 /* +---------------------------------------------------------------------------+
00034    |                     Mobile Robot Programming Toolkit (MRPT)               |
00035    |                          http://www.mrpt.org/                             |
00036    |                                                                           |
00037    | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file        |
00038    | See: http://www.mrpt.org/Authors - All rights reserved.                   |
00039    | Released under BSD License. See details in http://www.mrpt.org/License    |
00040    +---------------------------------------------------------------------------+ */
00041 
00042 
00043 #include "rtabmap/core/GeodeticCoords.h"
00044 
00045 #include <cmath>
00046 #ifndef M_PI
00047 #define M_PI       3.14159265358979323846
00048 #endif
00049 
00050 namespace rtabmap {
00051 
00052 
00053 inline double DEG2RAD(const double x) { return x*M_PI/180.0;}
00054 inline double RAD2DEG(const double x) { return x*180.0/M_PI;}
00055 inline double square(const double & value) {return value*value;}
00056 
00057 GeodeticCoords::GeodeticCoords() :
00058                 latitude_(0.0),
00059                 longitude_(0.0),
00060                 altitude_(0.0)
00061 {
00062 
00063 }
00064 GeodeticCoords::GeodeticCoords(double latitude, double longitude, double altitude) :
00065                 latitude_(latitude),
00066                 longitude_(longitude),
00067                 altitude_(altitude)
00068 {
00069 
00070 }
00071 
00072 //*---------------------------------------------------------------
00073 //                      geodeticToGeocentric_WGS84
00074 // ---------------------------------------------------------------*/
00075 cv::Point3d GeodeticCoords::toGeocentric_WGS84() const
00076 {
00077         // --------------------------------------------------------------------
00078         // See: http://en.wikipedia.org/wiki/Reference_ellipsoid
00079         //  Constants are for WGS84
00080         // --------------------------------------------------------------------
00081 
00082         static const double a = 6378137;                // Semi-major axis of the Earth (meters)
00083         static const double b = 6356752.3142;   // Semi-minor axis:
00084 
00085         static const double ae = acos(b/a);     // eccentricity:
00086         static const double cos2_ae_earth =  square(cos(ae)); // The cos^2 of the angular eccentricity of the Earth: // 0.993305619995739L;
00087         static const double sin2_ae_earth = square(sin(ae));  // The sin^2 of the angular eccentricity of the Earth: // 0.006694380004261L;
00088 
00089         const double lon  = DEG2RAD( double(this->longitude()) );
00090         const double lat  = DEG2RAD( double(this->latitude()) );
00091 
00092         // The radius of curvature in the prime vertical:
00093         const double N = a / std::sqrt( 1.0 - sin2_ae_earth*square( sin(lat) ) );
00094 
00095         // Generate 3D point:
00096         cv::Point3d out;
00097         out.x = (N+this->altitude())*cos(lat)*cos(lon);
00098         out.y = (N+this->altitude())*cos(lat)*sin(lon);
00099         out.z = (cos2_ae_earth*N+this->altitude())*sin(lat);
00100 
00101         return out;
00102 }
00103 
00104 
00105 /*---------------------------------------------------------------
00106                                 geodeticToENU_WGS84
00107  ---------------------------------------------------------------*/
00108 cv::Point3d GeodeticCoords::toENU_WGS84(const GeodeticCoords &origin) const
00109 {
00110         // --------------------------------------------------------------------
00111         //  Explanation: We compute the earth-centric coordinates first,
00112         //    then make a system transformation to local XYZ coordinates
00113         //    using a system of three orthogonal vectors as local reference.
00114         //
00115         // See: http://en.wikipedia.org/wiki/Reference_ellipsoid
00116         // (JLBC 21/DEC/2006)  (Fixed: JLBC 9/JUL/2008)
00117         // - Oct/2013, Emilio Sanjurjo: Fixed UP vector pointing exactly normal to ellipsoid surface.
00118         // --------------------------------------------------------------------
00119         // Generate 3D point:
00120         cv::Point3d     P_geocentric = this->toGeocentric_WGS84();
00121 
00122         // Generate reference 3D point:
00123         cv::Point3d P_geocentric_ref = origin.toGeocentric_WGS84();
00124 
00125         const double clat = cos(DEG2RAD(origin.latitude())), slat = sin(DEG2RAD(origin.latitude()));
00126         const double clon = cos(DEG2RAD(origin.longitude())), slon = sin(DEG2RAD(origin.longitude()));
00127 
00128         // Compute the resulting relative coordinates:
00129         // For using smaller numbers:
00130         P_geocentric -= P_geocentric_ref;
00131 
00132         // Optimized calculation: Local transformed coordinates of P_geo(x,y,z)
00133         //   after rotation given by the transposed rotation matrix from ENU -> ECEF.
00134         cv::Point3d out;
00135         out.x = -slon*P_geocentric.x + clon*P_geocentric.y;
00136         out.y = -clon*slat*P_geocentric.x -slon*slat*P_geocentric.y + clat*P_geocentric.z;
00137         out.z = clon*clat*P_geocentric.x + slon*clat*P_geocentric.y +slat*P_geocentric.z;
00138 
00139         return out;
00140 }
00141 
00142 void GeodeticCoords::fromGeocentric_WGS84(const cv::Point3d& geocentric)
00143 {
00144         static const double a = 6378137;                // Semi-major axis of the Earth (meters)
00145         static const double b = 6356752.3142;   // Semi-minor axis:
00146 
00147         const double sa2 = a*a;
00148         const double sb2 = b*b;
00149 
00150         const double e2 = (sa2 - sb2) / sa2;
00151         const double ep2 = (sa2 - sb2) / sb2;
00152         const double p = std::sqrt(geocentric.x * geocentric.x + geocentric.y * geocentric.y);
00153         const double theta = atan2(geocentric.z * a, p * b);
00154 
00155         longitude_ = atan2(geocentric.y, geocentric.x);
00156         latitude_ = atan2(
00157                         geocentric.z + ep2 * b * sin(theta) * sin(theta) * sin(theta),
00158                 p - e2 * a * cos(theta) * cos(theta) * cos(theta));
00159 
00160         const double clat = cos(latitude_);
00161         const double slat = sin(latitude_);
00162         const double N = sa2 / std::sqrt(sa2 * clat * clat + sb2 * slat * slat);
00163 
00164         altitude_ = p / clat - N;
00165         longitude_ = RAD2DEG(longitude_);
00166         latitude_ = RAD2DEG(latitude_);
00167 }
00168 
00169 void GeodeticCoords::fromENU_WGS84(const cv::Point3d& enu, const GeodeticCoords& origin)
00170 {
00171         fromGeocentric_WGS84(ENU_WGS84ToGeocentric_WGS84(enu, origin));
00172 }
00173 
00174 cv::Point3d GeodeticCoords::ENU_WGS84ToGeocentric_WGS84(const cv::Point3d& enu, const GeodeticCoords& origin)
00175 {
00176         // Generate reference 3D point:
00177         cv::Point3f originGeocentric;
00178         originGeocentric = origin.toGeocentric_WGS84();
00179 
00180         cv::Vec3d P_ref(originGeocentric.x, originGeocentric.y, originGeocentric.z);
00181 
00182         // Z axis -> In direction out-ward the center of the Earth:
00183         cv::Vec3d REF_X, REF_Y, REF_Z;
00184         REF_Z = cv::normalize(P_ref);
00185 
00186         // 1st column: Starting at the reference point, move in the tangent
00187         // direction
00188         //   east-ward: I compute this as the derivative of P_ref wrt "longitude":
00189         //      A_east[0] =-(N+in_height_meters)*cos(lat)*sin(lon);  --> -Z[1]
00190         //      A_east[1] = (N+in_height_meters)*cos(lat)*cos(lon);  -->  Z[0]
00191         //      A_east[2] = 0;                                       -->  0
00192         // ---------------------------------------------------------------------------
00193         cv::Vec3d AUX_X(-REF_Z[1], REF_Z[0], 0);
00194         REF_X = cv::normalize(AUX_X);
00195 
00196         // 2nd column: The cross product:
00197         REF_Y = REF_Z.cross(REF_X);
00198 
00199         cv::Point3d out_coords;
00200         out_coords.x =
00201                 REF_X[0] * enu.x + REF_Y[0] * enu.y + REF_Z[0] * enu.z + originGeocentric.x;
00202         out_coords.y =
00203                 REF_X[1] * enu.x + REF_Y[1] * enu.y + REF_Z[1] * enu.z + originGeocentric.y;
00204         out_coords.z =
00205                 REF_X[2] * enu.x + REF_Y[2] * enu.y + REF_Z[2] * enu.z + originGeocentric.z;
00206 
00207         return out_coords;
00208 }
00209 
00210 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:20