Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Periph: Add probe continuous checks to airspeed and compass #26874

Merged
merged 1 commit into from
Apr 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading