Main MRPT website > C++ reference for MRPT 1.5.6
Classes | Namespaces | Functions
[mrpt-topography]

Detailed Description

Back to list of all libraries | See all modules

Library mrpt-topography


Conversion and useful data structures to handle topographic data, perform geoid transformations, geocentric coordinates, etc...

See mrpt::topography

Classes

struct  mrpt::topography::TCoords
 A coordinate that is stored as a simple "decimal" angle in degrees, but can be retrieved/set in the form of DEGREES + arc-MINUTES + arc-SECONDS. More...
 
struct  mrpt::topography::TEllipsoid
 
struct  mrpt::topography::TGeodeticCoords
 A set of geodetic coordinates: latitude, longitude and height, defined over a given geoid (typically, WGS84) More...
 
struct  mrpt::topography::TDatum7Params
 Parameters for a topographic transfomation. More...
 
struct  mrpt::topography::TDatum7Params_TOPCON
 
struct  mrpt::topography::TDatum10Params
 Parameters for a topographic transfomation. More...
 
struct  mrpt::topography::TDatumHelmert2D
 Parameters for a topographic transfomation. More...
 
struct  mrpt::topography::TDatumHelmert2D_TOPCON
 
struct  mrpt::topography::TDatumHelmert3D
 Parameters for a topographic transfomation. More...
 
struct  mrpt::topography::TDatumHelmert3D_TOPCON
 Parameters for a topographic transfomation. More...
 
struct  mrpt::topography::TDatum1DTransf
 Parameters for a topographic transfomation. More...
 
struct  mrpt::topography::TDatumTransfInterpolation
 Parameters for a topographic transfomation. More...
 
struct  mrpt::topography::TPathFromRTKInfo
 Used to return optional information from mrpt::topography::path_from_rtk_gps. More...
 

Namespaces

 mrpt::topography
 This namespace provides topography helper functions, coordinate transformations.
 

Functions

void TOPO_IMPEXP mrpt::topography::path_from_rtk_gps (mrpt::poses::CPose3DInterpolator &robot_path, const mrpt::obs::CRawlog &rawlog, size_t rawlog_first, size_t rawlog_last, bool isGUI=false, bool disableGPSInterp=false, int path_smooth_filter_size=2, TPathFromRTKInfo *outInfo=NULL)
 Reconstruct the path of a vehicle equipped with 3 RTK GPSs. More...
 

Topography coordinate conversion functions

void TOPO_IMPEXP mrpt::topography::geodeticToENU_WGS84 (const TGeodeticCoords &in_coords, mrpt::math::TPoint3D &out_ENU_point, const TGeodeticCoords &in_coords_origin)
 Coordinates transformation from longitude/latitude/height to ENU (East-North-Up) X/Y/Z coordinates The WGS84 ellipsoid is used for the transformation. More...
 
void TOPO_IMPEXP mrpt::topography::ENUToGeocentric (const mrpt::math::TPoint3D &in_ENU_point, const TGeodeticCoords &in_coords_origin, TGeocentricCoords &out_coords, const TEllipsoid &ellip)
 ENU to geocentric coordinates. More...
 
void TOPO_IMPEXP mrpt::topography::geocentricToENU_WGS84 (const mrpt::math::TPoint3D &in_geocentric_point, mrpt::math::TPoint3D &out_ENU_point, const TGeodeticCoords &in_coords_origin)
 ENU to EFEC (Geocentric) coordinates. More...
 
void TOPO_IMPEXP mrpt::topography::geocentricToENU_WGS84 (const std::vector< mrpt::math::TPoint3D > &in_geocentric_points, std::vector< mrpt::math::TPoint3D > &out_ENU_points, const TGeodeticCoords &in_coords_origin)
 
void TOPO_IMPEXP mrpt::topography::geodeticToGeocentric_WGS84 (const TGeodeticCoords &in_coords, mrpt::math::TPoint3D &out_point)
 Coordinates transformation from longitude/latitude/height to geocentric X/Y/Z coordinates (with a WGS84 geoid). More...
 
void TOPO_IMPEXP mrpt::topography::geodeticToGeocentric (const TGeodeticCoords &in_coords, TGeocentricCoords &out_point, const TEllipsoid &ellip)
 Coordinates transformation from longitude/latitude/height to geocentric X/Y/Z coordinates (with an specified geoid). More...
 
void TOPO_IMPEXP mrpt::topography::geocentricToGeodetic (const TGeocentricCoords &in_point, TGeodeticCoords &out_coords, const TEllipsoid &ellip=TEllipsoid::Ellipsoid_WGS84())
 Coordinates transformation from geocentric X/Y/Z coordinates to longitude/latitude/height. More...
 
void TOPO_IMPEXP mrpt::topography::transform7params (const mrpt::math::TPoint3D &in_point, const TDatum7Params &in_datum, mrpt::math::TPoint3D &out_point)
 7-parameter Bursa-Wolf transformation: [ X Y Z ]_WGS84 = [ dX dY dZ ] + ( 1 + dS ) [ 1 RZ -RY; -RZ 1 RX; RY -RX 1 ] [ X Y Z ]_local More...
 
void TOPO_IMPEXP mrpt::topography::transform7params_TOPCON (const mrpt::math::TPoint3D &in_point, const TDatum7Params_TOPCON &in_datum, mrpt::math::TPoint3D &out_point)
 7-parameter Bursa-Wolf transformation TOPCON: [ X Y Z ]_WGS84 = [ dX dY dZ ] + ( 1 + dS ) [ 1 RZ -RY; -RZ 1 RX; RY -RX 1 ] [ X Y Z ]_local More...
 
void TOPO_IMPEXP mrpt::topography::transform10params (const mrpt::math::TPoint3D &in_point, const TDatum10Params &in_datum, mrpt::math::TPoint3D &out_point)
 10-parameter Molodensky-Badekas transformation: [ X Y Z ]_WGS84 = [ dX dY dZ ] + ( 1 + dS ) [ 1 RZ -RY; -RZ 1 RX; RY -RX 1 ] [ X-Xp Y-Yp Z-Zp ]_local + [Xp Yp Zp] More...
 
void TOPO_IMPEXP mrpt::topography::transformHelmert2D (const mrpt::math::TPoint2D &p, const TDatumHelmert2D &d, mrpt::math::TPoint2D &o)
 Helmert 2D transformation: [ X Y ]_WGS84 = [ dX dY ] + ( 1 + dS ) [ cos(alpha) -sin(alpha); sin(alpha) cos(alpha) ] [ X-Xp Y-Yp Z-Zp ]_local + [Xp Yp Zp]. More...
 
void TOPO_IMPEXP mrpt::topography::transformHelmert2D_TOPCON (const mrpt::math::TPoint2D &p, const TDatumHelmert2D_TOPCON &d, mrpt::math::TPoint2D &o)
 Helmert 2D transformation: [ X Y ]_WGS84 = [ dX dY ] + ( 1 + dS ) [ cos(alpha) -sin(alpha); sin(alpha) cos(alpha) ] [ X-Xp Y-Yp Z-Zp ]_local + [Xp Yp Zp]. More...
 
void TOPO_IMPEXP mrpt::topography::transformHelmert3D (const mrpt::math::TPoint3D &p, const TDatumHelmert3D &d, mrpt::math::TPoint3D &o)
 Helmert3D transformation: [ X Y Z ]_WGS84 = [ dX dY dZ ] + ( 1 + dS ) [ 1 -RZ RY; RZ 1 -RX; -RY RX 1 ] [ X Y Z ]_local. More...
 
void TOPO_IMPEXP mrpt::topography::transformHelmert3D_TOPCON (const mrpt::math::TPoint3D &p, const TDatumHelmert3D_TOPCON &d, mrpt::math::TPoint3D &o)
 Helmert 3D transformation: [ X Y ]_WGS84 = [ dX dY ] + ( 1 + dS ) [ cos(alpha) -sin(alpha); sin(alpha) cos(alpha) ] [ X-Xp Y-Yp Z-Zp ]_local + [Xp Yp Zp]. More...
 
void TOPO_IMPEXP mrpt::topography::transform1D (const mrpt::math::TPoint3D &p, const TDatum1DTransf &d, mrpt::math::TPoint3D &o)
 1D transformation: [ Z ]_WGS84 = (dy * X - dx * Y + Z)*(1+e)+DZ More...
 
void TOPO_IMPEXP mrpt::topography::transfInterpolation (const mrpt::math::TPoint3D &p, const TDatumTransfInterpolation &d, mrpt::math::TPoint3D &o)
 Interpolation: [ Z ]_WGS84 = (dy * X - dx * Y + Z)*(1+e)+DZ. More...
 
void TOPO_IMPEXP mrpt::topography::UTMToGeodetic (double X, double Y, int zone, char hem, double &out_lon, double &out_lat, const TEllipsoid &ellip=TEllipsoid::Ellipsoid_WGS84())
 Returns the Geodetic coordinates of the UTM input point. More...
 
void mrpt::topography::UTMToGeodetic (const TUTMCoords &UTMCoords, const int &zone, const char &hem, TGeodeticCoords &GeodeticCoords, const TEllipsoid &ellip=TEllipsoid::Ellipsoid_WGS84())
 Returns the Geodetic coordinates of the UTM input point. More...
 
void TOPO_IMPEXP mrpt::topography::GeodeticToUTM (double in_latitude_degrees, double in_longitude_degrees, double &out_UTM_x, double &out_UTM_y, int &out_UTM_zone, char &out_UTM_latitude_band, const TEllipsoid &ellip=TEllipsoid::Ellipsoid_WGS84())
 Convert latitude and longitude coordinates into UTM coordinates, computing the corresponding UTM zone and latitude band. More...
 
void TOPO_IMPEXP mrpt::topography::geodeticToUTM (const TGeodeticCoords &GeodeticCoords, TUTMCoords &UTMCoords, int &UTMZone, char &UTMLatitudeBand, const TEllipsoid &ellip=TEllipsoid::Ellipsoid_WGS84())
 
void mrpt::topography::GeodeticToUTM (const TGeodeticCoords &GeodeticCoords, TUTMCoords &UTMCoords, int &UTMZone, char &UTMLatitudeBand, const TEllipsoid &ellip=TEllipsoid::Ellipsoid_WGS84())
 Convert latitude and longitude coordinates into UTM coordinates, computing the corresponding UTM zone and latitude band. More...
 

Miscellaneous

=======================================================================

void TOPO_IMPEXP mrpt::topography::ENU_axes_from_WGS84 (double in_longitude_reference_degrees, double in_latitude_reference_degrees, double in_height_reference_meters, mrpt::math::TPose3D &out_ENU, bool only_angles=false)
 Returns the East-North-Up (ENU) coordinate system associated to the given point. More...
 
void mrpt::topography::ENU_axes_from_WGS84 (const TGeodeticCoords &in_coords, mrpt::math::TPose3D &out_ENU, bool only_angles=false)
 

Data structures

typedef mrpt::math::TPoint3D mrpt::topography::TUTMCoords
 
typedef mrpt::math::TPoint3D mrpt::topography::TGeocentricCoords
 
bool TOPO_IMPEXP mrpt::topography::operator== (const TCoords &a, const TCoords &o)
 
bool TOPO_IMPEXP mrpt::topography::operator!= (const TCoords &a, const TCoords &o)
 
std::ostream TOPO_IMPEXPmrpt::topography::operator<< (std::ostream &out, const TCoords &o)
 
bool TOPO_IMPEXP mrpt::topography::operator== (const TGeodeticCoords &a, const TGeodeticCoords &o)
 
bool TOPO_IMPEXP mrpt::topography::operator!= (const TGeodeticCoords &a, const TGeodeticCoords &o)
 

Typedef Documentation

◆ TGeocentricCoords

Definition at line 118 of file data_types.h.

◆ TUTMCoords

Definition at line 117 of file data_types.h.

Function Documentation

◆ ENU_axes_from_WGS84() [1/2]

void mrpt::topography::ENU_axes_from_WGS84 ( double  in_longitude_reference_degrees,
double  in_latitude_reference_degrees,
double  in_height_reference_meters,
mrpt::math::TPose3D out_ENU,
bool  only_angles = false 
)

Returns the East-North-Up (ENU) coordinate system associated to the given point.

This is the reference employed in geodeticToENU_WGS84

Parameters
only_anglesIf set to true, the (x,y,z) fields will be left zeroed.
Note
The "Up" (Z) direction in ENU is the normal to the ellipsoid, which coincides with the direction of an increasing geodetic height.
See also
geodeticToENU_WGS84

Definition at line 128 of file conversions.cpp.

References DEG2RAD, mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.

Referenced by mrpt::topography::ENU_axes_from_WGS84().

◆ ENU_axes_from_WGS84() [2/2]

void mrpt::topography::ENU_axes_from_WGS84 ( const TGeodeticCoords in_coords,
mrpt::math::TPose3D out_ENU,
bool  only_angles = false 
)
inline

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 271 of file conversions.h.

References mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::TGeodeticCoords::height, mrpt::topography::TGeodeticCoords::lat, and mrpt::topography::TGeodeticCoords::lon.

◆ ENUToGeocentric()

void mrpt::topography::ENUToGeocentric ( const mrpt::math::TPoint3D p,
const TGeodeticCoords in_coords_origin,
TGeocentricCoords out_coords,
const TEllipsoid ellip 
)

◆ geocentricToENU_WGS84() [1/2]

void mrpt::topography::geocentricToENU_WGS84 ( const mrpt::math::TPoint3D in_geocentric_point,
mrpt::math::TPoint3D out_ENU_point,
const TGeodeticCoords in_coords_origin 
)

◆ geocentricToENU_WGS84() [2/2]

void mrpt::topography::geocentricToENU_WGS84 ( const std::vector< mrpt::math::TPoint3D > &  in_geocentric_points,
std::vector< mrpt::math::TPoint3D > &  out_ENU_points,
const TGeodeticCoords in_coords_origin 
)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 74 of file conversions.cpp.

References DEG2RAD, mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::TGeodeticCoords::lat, mrpt::topography::TGeodeticCoords::lon, mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.

◆ geocentricToGeodetic()

void mrpt::topography::geocentricToGeodetic ( const TGeocentricCoords in_point,
TGeodeticCoords out_coords,
const TEllipsoid ellip = TEllipsoid::Ellipsoid_WGS84() 
)

◆ geodeticToENU_WGS84()

void mrpt::topography::geodeticToENU_WGS84 ( const TGeodeticCoords in_coords,
mrpt::math::TPoint3D out_ENU_point,
const TGeodeticCoords in_coords_origin 
)

Coordinates transformation from longitude/latitude/height to ENU (East-North-Up) X/Y/Z coordinates The WGS84 ellipsoid is used for the transformation.

The coordinates are in 3D relative to some user-provided point, with local X axis being east-ward, Y north-ward, Z up-ward. For an explanation, refer to http://en.wikipedia.org/wiki/Reference_ellipsoid

See also
coordinatesTransformation_WGS84_geocentric, ENU_axes_from_WGS84, ENUToGeocentric
Note
The "Up" (Z) direction in ENU is the normal to the ellipsoid, which coincides with the direction of an increasing geodetic height.

Definition at line 104 of file conversions.cpp.

References mrpt::topography::geocentricToENU_WGS84(), and mrpt::topography::geodeticToGeocentric_WGS84().

Referenced by mrpt::topography::path_from_rtk_gps(), and TEST().

◆ geodeticToGeocentric()

void mrpt::topography::geodeticToGeocentric ( const TGeodeticCoords in_coords,
TGeocentricCoords out_point,
const TEllipsoid ellip 
)

◆ geodeticToGeocentric_WGS84()

void mrpt::topography::geodeticToGeocentric_WGS84 ( const TGeodeticCoords in_coords,
mrpt::math::TPoint3D out_point 
)

Coordinates transformation from longitude/latitude/height to geocentric X/Y/Z coordinates (with a WGS84 geoid).

The WGS84 ellipsoid is used for the transformation. The coordinates are in 3D where the reference is the center of the Earth. For an explanation, refer to http://en.wikipedia.org/wiki/Reference_ellipsoid

See also
geodeticToENU_WGS84

Definition at line 164 of file conversions.cpp.

References DEG2RAD, mrpt::topography::TGeodeticCoords::height, mrpt::topography::TGeodeticCoords::lat, mrpt::obs::gnss::lat, mrpt::topography::TGeodeticCoords::lon, mrpt::obs::gnss::lon, mrpt::math::square(), mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.

Referenced by mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::geocentricToENU_WGS84(), and mrpt::topography::geodeticToENU_WGS84().

◆ GeodeticToUTM() [1/2]

void mrpt::topography::GeodeticToUTM ( double  in_latitude_degrees,
double  in_longitude_degrees,
double &  out_UTM_x,
double &  out_UTM_y,
int &  out_UTM_zone,
char &  out_UTM_latitude_band,
const TEllipsoid ellip = TEllipsoid::Ellipsoid_WGS84() 
)

Convert latitude and longitude coordinates into UTM coordinates, computing the corresponding UTM zone and latitude band.

This method is based on public code by Gabriel Ruiz Martinez and Rafael Palacios. Example:

Input:
Lat=40.3154333 Lon=-3.4857166
Output:
x = 458731
y = 4462881
utm_zone = 30
utm_band = T
See also
http://www.mathworks.com/matlabcentral/fileexchange/10915

Definition at line 373 of file conversions.cpp.

References mrpt::obs::gnss::a1, mrpt::obs::gnss::a2, DEG2RAD, mrpt::utils::fix(), mrpt::obs::gnss::lat, mrpt::obs::gnss::lon, mrpt::topography::TEllipsoid::sa, mrpt::topography::TEllipsoid::sb, and mrpt::math::square().

Referenced by mrpt::topography::GeodeticToUTM().

◆ geodeticToUTM()

void mrpt::topography::geodeticToUTM ( const TGeodeticCoords GeodeticCoords,
TUTMCoords UTMCoords,
int &  UTMZone,
char &  UTMLatitudeBand,
const TEllipsoid ellip = TEllipsoid::Ellipsoid_WGS84() 
)

◆ GeodeticToUTM() [2/2]

void mrpt::topography::GeodeticToUTM ( const TGeodeticCoords GeodeticCoords,
TUTMCoords UTMCoords,
int &  UTMZone,
char &  UTMLatitudeBand,
const TEllipsoid ellip = TEllipsoid::Ellipsoid_WGS84() 
)
inline

Convert latitude and longitude coordinates into UTM coordinates, computing the corresponding UTM zone and latitude band.

This method is based on public code by Gabriel Ruiz Martinez and Rafael Palacios. Example:

Input:
Lat=40.3154333 Lon=-3.4857166
Output:
x = 458731
y = 4462881
utm_zone = 30
utm_band = T
See also
http://www.mathworks.com/matlabcentral/fileexchange/10915

Definition at line 238 of file conversions.h.

References mrpt::topography::GeodeticToUTM(), mrpt::topography::TGeodeticCoords::height, mrpt::topography::TGeodeticCoords::lat, mrpt::topography::TGeodeticCoords::lon, mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.

◆ operator!=() [1/2]

bool mrpt::topography::operator!= ( const TCoords a,
const TCoords o 
)

Definition at line 26 of file conversions.cpp.

◆ operator!=() [2/2]

bool mrpt::topography::operator!= ( const TGeodeticCoords a,
const TGeodeticCoords o 
)

Definition at line 28 of file conversions.cpp.

◆ operator<<()

std::ostream & mrpt::topography::operator<< ( std::ostream &  out,
const TCoords o 
)

Definition at line 42 of file conversions.cpp.

References mrpt::topography::TCoords::getAsString().

◆ operator==() [1/2]

bool mrpt::topography::operator== ( const TCoords a,
const TCoords o 
)

Definition at line 25 of file conversions.cpp.

References mrpt::topography::TCoords::decimal_value.

◆ operator==() [2/2]

bool mrpt::topography::operator== ( const TGeodeticCoords a,
const TGeodeticCoords o 
)

◆ path_from_rtk_gps()

void mrpt::topography::path_from_rtk_gps ( mrpt::poses::CPose3DInterpolator robot_path,
const mrpt::obs::CRawlog rawlog,
size_t  rawlog_first,
size_t  rawlog_last,
bool  isGUI = false,
bool  disableGPSInterp = false,
int  path_smooth_filter_size = 2,
TPathFromRTKInfo outInfo = NULL 
)

Reconstruct the path of a vehicle equipped with 3 RTK GPSs.

Parameters
robot_path[OUT] The reconstructed vehicle path
rawlog[IN] The dataset. It must contain mrpt::obs::CObservationGPS observations with GGA datums.
rawlog_first[IN] The index of the first entry to process (first=0)
rawlog_last[IN] The index of the last entry to process
isGUI[IN] If set to true, some progress dialogs will be shown during the computation (requires MRPT built with support for wxWidgets).
disableGPSInterp[IN] Whether to interpolate missing GPS readings between very close datums.
path_smooth_filter_size[IN] Size of the window in the pitch & roll noise filtering.
outInfo[OUT] Optional output: additional information from the optimization

For more details on the method, refer to the paper: (...)

See also
mrpt::topography

Definition at line 50 of file path_from_rtk_gps.cpp.

References mrpt::obs::gnss::Message_NMEA_GGA::content_t::altitude_meters, ASSERT_, mrpt::math::averageWrap2Pi(), mrpt::poses::CPoseInterpolatorBase< DIM >::begin(), mrpt::topography::TPathFromRTKInfo::best_gps_path, mrpt::poses::CPose3DPDFGaussian::changeCoordinatesReference(), CLASS_ID, mrpt::poses::CPoseInterpolatorBase< DIM >::clear(), mrpt::poses::CPose3DPDFGaussian::cov, mrpt::math::TPoint3D::distanceTo(), mrpt::poses::CPoseInterpolatorBase< DIM >::end(), mrpt::obs::gnss::Message_NMEA_GGA::fields, mrpt::obs::gnss::Message_NMEA_GGA::content_t::fix_quality, mrpt::topography::geodeticToENU_WGS84(), mrpt::obs::CRawlog::getAsObservation(), mrpt::obs::gnss::Message_NMEA_GGA::getAsStruct(), mrpt::obs::CRawlog::getCommentTextAsConfigFile(), mrpt::obs::CRawlog::getType(), mrpt::poses::imSSLSLL, mrpt::poses::CPoseInterpolatorBase< DIM >::insert(), mrpt::obs::gnss::Message_NMEA_GGA::content_t::latitude_degrees, mrpt::obs::gnss::Message_NMEA_GGA::content_t::longitude_degrees, mrpt::topography::TPathFromRTKInfo::mahalabis_quality_measure, mrpt::math::mahalanobisDistance(), make_set(), mrpt::poses::CPose3DPDFGaussian::mean, MRPT_CHECK_NORMAL_NUMBER, MRPT_END, MRPT_START, MRPT_UNUSED_PARAM, mrpt::poses::CPose3DQuat::quat(), mrpt::math::CQuaternion< T >::r(), mrpt::utils::CConfigFileBase::read_double(), mrpt::utils::CConfigFileBase::read_matrix(), mrpt::tfest::se3_l2(), mrpt::poses::CPose3D::setFromValues(), mrpt::poses::CPoseInterpolatorBase< DIM >::setInterpolationMethod(), mrpt::poses::CPoseInterpolatorBase< DIM >::setMaxTimeInterpolation(), mrpt::poses::CPoseInterpolatorBase< DIM >::size(), mrpt::obs::CRawlog::size(), mrpt::math::TPoint3D::sqrDistanceTo(), mrpt::math::square(), THROW_EXCEPTION, mrpt::system::timeDifference(), mrpt::topography::TPathFromRTKInfo::vehicle_uncertainty, mrpt::topography::TPathFromRTKInfo::W_star, mrpt::math::CQuaternion< T >::x(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x(), mrpt::math::TPoint3D::x, mrpt::math::CQuaternion< T >::y(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y(), mrpt::math::TPoint3D::y, mrpt::math::CQuaternion< T >::z(), and mrpt::math::TPoint3D::z.

Referenced by TEST().

◆ transfInterpolation()

void mrpt::topography::transfInterpolation ( const mrpt::math::TPoint3D p,
const TDatumTransfInterpolation d,
mrpt::math::TPoint3D o 
)

Interpolation: [ Z ]_WGS84 = (dy * X - dx * Y + Z)*(1+e)+DZ.

1D transformation: [ X;Y ]_WGS84 = [X;Y]_locales+[1 -sin(d.beta);0 cos(d.beta)]*[x*d.dSx;y*d.dSy ]

See also
transformHelmert3D

Definition at line 577 of file conversions.cpp.

References mrpt::topography::TDatumTransfInterpolation::beta, mrpt::topography::TDatumTransfInterpolation::dSx, mrpt::topography::TDatumTransfInterpolation::dSy, mrpt::topography::TDatumTransfInterpolation::dX, mrpt::topography::TDatumTransfInterpolation::dY, mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.

◆ transform10params()

void mrpt::topography::transform10params ( const mrpt::math::TPoint3D p,
const TDatum10Params d,
mrpt::math::TPoint3D o 
)

◆ transform1D()

void mrpt::topography::transform1D ( const mrpt::math::TPoint3D p,
const TDatum1DTransf d,
mrpt::math::TPoint3D o 
)

◆ transform7params()

void mrpt::topography::transform7params ( const mrpt::math::TPoint3D p,
const TDatum7Params d,
mrpt::math::TPoint3D o 
)

◆ transform7params_TOPCON()

void mrpt::topography::transform7params_TOPCON ( const mrpt::math::TPoint3D p,
const TDatum7Params_TOPCON d,
mrpt::math::TPoint3D o 
)

◆ transformHelmert2D()

void mrpt::topography::transformHelmert2D ( const mrpt::math::TPoint2D p,
const TDatumHelmert2D d,
mrpt::math::TPoint2D o 
)

Helmert 2D transformation: [ X Y ]_WGS84 = [ dX dY ] + ( 1 + dS ) [ cos(alpha) -sin(alpha); sin(alpha) cos(alpha) ] [ X-Xp Y-Yp Z-Zp ]_local + [Xp Yp Zp].

See also
transformHelmert3D

Definition at line 505 of file conversions.cpp.

References mrpt::topography::TDatumHelmert2D::alpha, mrpt::topography::TDatumHelmert2D::dS, mrpt::topography::TDatumHelmert2D::dX, mrpt::topography::TDatumHelmert2D::dY, mrpt::math::TPoint2D::x, mrpt::topography::TDatumHelmert2D::Xp, mrpt::math::TPoint2D::y, and mrpt::topography::TDatumHelmert2D::Yp.

◆ transformHelmert2D_TOPCON()

void mrpt::topography::transformHelmert2D_TOPCON ( const mrpt::math::TPoint2D p,
const TDatumHelmert2D_TOPCON d,
mrpt::math::TPoint2D o 
)

Helmert 2D transformation: [ X Y ]_WGS84 = [ dX dY ] + ( 1 + dS ) [ cos(alpha) -sin(alpha); sin(alpha) cos(alpha) ] [ X-Xp Y-Yp Z-Zp ]_local + [Xp Yp Zp].

See also
transformHelmert3D

Definition at line 523 of file conversions.cpp.

References mrpt::topography::TDatumHelmert2D_TOPCON::a, mrpt::topography::TDatumHelmert2D_TOPCON::b, mrpt::topography::TDatumHelmert2D_TOPCON::c, mrpt::topography::TDatumHelmert2D_TOPCON::d, mrpt::math::TPoint2D::x, and mrpt::math::TPoint2D::y.

◆ transformHelmert3D()

void mrpt::topography::transformHelmert3D ( const mrpt::math::TPoint3D p,
const TDatumHelmert3D d,
mrpt::math::TPoint3D o 
)

Helmert3D transformation: [ X Y Z ]_WGS84 = [ dX dY dZ ] + ( 1 + dS ) [ 1 -RZ RY; RZ 1 -RX; -RY RX 1 ] [ X Y Z ]_local.

Helmert 3D transformation: [ X Y ]_WGS84 = [ dX dY ] + ( 1 + dS ) [ cos(alpha) -sin(alpha); sin(alpha) cos(alpha) ] [ X-Xp Y-Yp Z-Zp ]_local + [Xp Yp Zp].

See also
transformHelmert2D
transformHelmert3D

Definition at line 536 of file conversions.cpp.

References mrpt::topography::TDatumHelmert3D::dS, mrpt::topography::TDatumHelmert3D::dX, mrpt::topography::TDatumHelmert3D::dY, mrpt::topography::TDatumHelmert3D::dZ, mrpt::topography::TDatumHelmert3D::Rx, mrpt::topography::TDatumHelmert3D::Ry, mrpt::topography::TDatumHelmert3D::Rz, and mrpt::topography::transform7params().

◆ transformHelmert3D_TOPCON()

void mrpt::topography::transformHelmert3D_TOPCON ( const mrpt::math::TPoint3D p,
const TDatumHelmert3D_TOPCON d,
mrpt::math::TPoint3D o 
)

◆ UTMToGeodetic() [1/2]

void mrpt::topography::UTMToGeodetic ( double  X,
double  Y,
int  zone,
char  hem,
double &  out_lon,
double &  out_lat,
const TEllipsoid ellip = TEllipsoid::Ellipsoid_WGS84() 
)

Returns the Geodetic coordinates of the UTM input point.

Parameters
XEast coordinate of the input point.
YNorth coordinate of the input point.
zonetime zone (Spanish: "huso").
hemhemisphere ('N'/'n' for North or 'S'/s' for South ). An exception will be raised on any other value.
ellipthe reference ellipsoid used for the transformation (default: WGS84)
out_latOut latitude, in degrees.
out_lonOut longitude, in degrees.

Definition at line 251 of file conversions.cpp.

References mrpt::obs::gnss::A1, mrpt::obs::gnss::a2, ASSERT_, mrpt::obs::gnss::b2, eps, RAD2DEG, mrpt::topography::TEllipsoid::sa, mrpt::topography::TEllipsoid::sb, and mrpt::math::square().

Referenced by mrpt::topography::UTMToGeodetic().

◆ UTMToGeodetic() [2/2]

void mrpt::topography::UTMToGeodetic ( const TUTMCoords UTMCoords,
const int &  zone,
const char &  hem,
TGeodeticCoords GeodeticCoords,
const TEllipsoid ellip = TEllipsoid::Ellipsoid_WGS84() 
)
inline

Returns the Geodetic coordinates of the UTM input point.

Parameters
UTMCoordsUTM input coordinates.
zonetime zone (Spanish: "huso").
hemhemisphere ('N'/'n' for North or 'S'/s' for South ). An exception will be raised on any other value.
GeodeticCoordsOut geodetic coordinates.
ellipthe reference ellipsoid used for the transformation (default: WGS84)

Definition at line 182 of file conversions.h.

References mrpt::topography::TCoords::decimal_value, mrpt::topography::TGeodeticCoords::height, mrpt::topography::TGeodeticCoords::lat, mrpt::topography::TGeodeticCoords::lon, mrpt::topography::UTMToGeodetic(), mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.




Page generated by Doxygen 1.8.14 for MRPT 1.5.6 Git: 4c65e8431 Tue Apr 24 08:18:17 2018 +0200 at lun oct 28 01:35:26 CET 2019