mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Periph: don't probe rangefinder continuously
This commit is contained in:
parent
41b74ec014
commit
84ac1ac41d
@ -1525,6 +1525,7 @@ void AP_Periph_FW::can_rangefinder_update(void)
|
||||
if (rangefinder.get_type(0) == RangeFinder::Type::NONE) {
|
||||
return;
|
||||
}
|
||||
#if CAN_PROBE_CONTINUOUS
|
||||
if (rangefinder.num_sensors() == 0) {
|
||||
uint32_t now = AP_HAL::millis();
|
||||
static uint32_t last_probe_ms;
|
||||
@ -1533,6 +1534,7 @@ void AP_Periph_FW::can_rangefinder_update(void)
|
||||
rangefinder.init(ROTATION_NONE);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
uint32_t now = AP_HAL::millis();
|
||||
static uint32_t last_update_ms;
|
||||
if (now - last_update_ms < 20) {
|
||||
|
Loading…
Reference in New Issue
Block a user