mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: Comments on WGS coordinate conversions
This commit is contained in:
parent
1ed716976c
commit
398f32d538
@ -146,8 +146,14 @@ float wrap_PI(float angle_in_radians);
|
||||
void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon);
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
//Convert between LLH and ECEF coordinate systems
|
||||
// Converts from WGS84 geodetic coordinates (lat, lon, height)
|
||||
// into WGS84 Earth Centered, Earth Fixed (ECEF) coordinates
|
||||
// (X, Y, Z)
|
||||
void wgsllh2ecef(const Vector3d &llh, Vector3d &ecef);
|
||||
|
||||
// Converts from WGS84 Earth Centered, Earth Fixed (ECEF)
|
||||
// coordinates (X, Y, Z), into WHS84 geodetic
|
||||
// coordinates (lat, lon, height)
|
||||
void wgsecef2llh(const Vector3d &ecef, Vector3d &llh);
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user