Skip to content

Commit

Permalink
AP_ADSB: populate altitude via pressure for ADSB-Out
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Feb 22, 2017
1 parent 1de1988 commit 5adbf9b
Showing 1 changed file with 6 additions and 1 deletion.
7 changes: 6 additions & 1 deletion libraries/AP_ADSB/AP_ADSB.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}



Expand Down

0 comments on commit 5adbf9b

Please sign in to comment.