Skip to content

Commit

Permalink
Periph: Add probe continuous checks to airspeed and compass
Browse files Browse the repository at this point in the history
  • Loading branch information
MattKear committed Apr 23, 2024
1 parent 3c8b3be commit 809fab7
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion Tools/AP_Periph/airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/compass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down

0 comments on commit 809fab7

Please sign in to comment.