mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 00:33:56 -04:00
AP_Baro: fixed baro health for AP_Periph
This commit is contained in:
parent
cc5ccc28ec
commit
8e4138b503
@ -64,6 +64,10 @@
|
||||
#define HAL_BARO_PROBE_EXT_DEFAULT 0
|
||||
#endif
|
||||
|
||||
#ifdef HAL_BUILD_AP_PERIPH
|
||||
#define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// table of user settable parameters
|
||||
@ -607,6 +611,14 @@ void AP_Baro::init(void)
|
||||
AP_BoardConfig::config_error("Baro: unable to initialise driver");
|
||||
}
|
||||
#endif
|
||||
#ifdef HAL_BUILD_AP_PERIPH
|
||||
// AP_Periph always is set calibrated. We only want the pressure,
|
||||
// so ground calibration is unnecessary
|
||||
for (uint8_t i=0; i<_num_sensors; i++) {
|
||||
sensors[i].calibrated = true;
|
||||
sensors[i].alt_ok = true;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user