mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Periph: Add probe continuous checks to airspeed and compass
This commit is contained in:
parent
84900473de
commit
1a39bd1a6e
@ -21,7 +21,7 @@ void AP_Periph_FW::can_airspeed_update(void)
|
||||
return;
|
||||
}
|
||||
#if AP_PERIPH_PROBE_CONTINUOUS
|
||||
if (!airspeed.healthy()) {
|
||||
if (option_is_set(PeriphOptions::PROBE_CONTINUOUS) && !hal.util->get_soft_armed() && !airspeed.healthy()) {
|
||||
uint32_t now = AP_HAL::millis();
|
||||
static uint32_t last_probe_ms;
|
||||
if (now - last_probe_ms >= 1000) {
|
||||
|
@ -40,7 +40,7 @@ void AP_Periph_FW::can_mag_update(void)
|
||||
compass.read();
|
||||
|
||||
#if AP_PERIPH_PROBE_CONTINUOUS
|
||||
if (compass.get_count() == 0) {
|
||||
if (option_is_set(PeriphOptions::PROBE_CONTINUOUS) && !hal.util->get_soft_armed() && (compass.get_count() == 0)) {
|
||||
static uint32_t last_probe_ms;
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (now - last_probe_ms >= 1000) {
|
||||
|
Loading…
Reference in New Issue
Block a user