mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Periph: MSP fix last baro ms
This commit is contained in:
parent
3c83eecf78
commit
c8d874676f
@ -128,12 +128,12 @@ void AP_Periph_FW::send_msp_baro(void)
|
||||
if (msp.last_baro_ms == baro.get_last_update(0)) {
|
||||
return;
|
||||
}
|
||||
msp.last_baro_ms = baro.get_last_update(0);
|
||||
if (!baro.healthy()) {
|
||||
// don't send any data
|
||||
return;
|
||||
}
|
||||
|
||||
msp.last_baro_ms = baro.get_last_update(0);
|
||||
|
||||
p.instance = 0;
|
||||
p.time_ms = msp.last_baro_ms;
|
||||
p.pressure_pa = baro.get_pressure();
|
||||
|
Loading…
Reference in New Issue
Block a user