Browse Source

AP_ADSB: populate altitude via pressure for ADSB-Out

fixes https://github.com/ArduPilot/ardupilot/issues/5424
master
Tom Pittenger 8 years ago committed by Tom Pittenger
parent
commit
5adbf9b232
  1. 7
      libraries/AP_ADSB/AP_ADSB.cpp

7
libraries/AP_ADSB/AP_ADSB.cpp

@ -518,7 +518,12 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan) @@ -518,7 +518,12 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan)
// --------------
// Unknowns
// TODO: implement http://www.srh.noaa.gov/images/epz/wxcalc/pressureAltitude.pdf
int32_t altPres = INT_MAX; //_ahrs.get_baro().get_altitude() relative to home, not MSL
AP_Baro baro = _ahrs.get_baro();
int32_t altPres = INT_MAX;
if (baro.healthy()) {
// Altitude difference between 101325 (Pascals) and current pressure. Result in millimeters
altPres = baro.get_altitude_difference(101325, baro.get_pressure()) * 1E3; // convert m to mm;
}

Loading…
Cancel
Save