GPS: Add height above the ellipsoid info

Modification of the GPS message, add height above the ellipsoid info.
This commit is contained in:
Amir 2015-11-27 22:28:41 +01:00
parent ab95b4706e
commit c23562c9ed
2 changed files with 2 additions and 0 deletions

View File

@ -3,6 +3,7 @@ uint64 timestamp_position # Timestamp for position information
int32 lat # Latitude in 1E-7 degrees
int32 lon # Longitude in 1E-7 degrees
int32 alt # Altitude in 1E-3 meters (millimeters) above MSL
int32 alt_ellipsoid # Altitude in 1E-3 meters (millimeters) above Ellipsoid
uint64 timestamp_variance
float32 s_variance_m_s # speed accuracy estimate m/s

View File

@ -874,6 +874,7 @@ UBX::payload_rx_done(void)
_gps_position->alt = _buf.payload_rx_nav_posllh.hMSL;
_gps_position->eph = (float)_buf.payload_rx_nav_posllh.hAcc * 1e-3f; // from mm to m
_gps_position->epv = (float)_buf.payload_rx_nav_posllh.vAcc * 1e-3f; // from mm to m
_gps_position->alt_ellipsoid = _buf.payload_rx_nav_posllh.height;
_gps_position->timestamp_position = hrt_absolute_time();