AP_ADSB: send absolute height in GPS packet to MXS device
Documentation specifies WGS-84 ellipsoid.
This commit is contained in:
parent
e5ec596a03
commit
5dbe08c454
@ -641,7 +641,7 @@ void AP_ADSB_Sagetech_MXS::send_gps_msg()
|
||||
}
|
||||
|
||||
int32_t height;
|
||||
if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, height)) {
|
||||
if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, height)) {
|
||||
gps.height = height * 0.01;
|
||||
} else {
|
||||
gps.height = 0.0;
|
||||
|
Loading…
Reference in New Issue
Block a user