mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: Rate limit EFI driver updates
Also remove the last update variables for features that were compiled out.
This commit is contained in:
parent
3c6ddda5e8
commit
00a5c92635
|
@ -371,13 +371,26 @@ public:
|
|||
|
||||
static const AP_Param::Info var_info[];
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_EFI
|
||||
uint32_t last_efi_update_ms;
|
||||
#endif
|
||||
#ifdef HAL_PERIPH_ENABLE_MAG
|
||||
uint32_t last_mag_update_ms;
|
||||
#endif
|
||||
#ifdef HAL_PERIPH_ENABLE_GPS
|
||||
uint32_t last_gps_update_ms;
|
||||
uint32_t last_gps_yaw_ms;
|
||||
#endif
|
||||
uint32_t last_relposheading_ms;
|
||||
#ifdef HAL_PERIPH_ENABLE_BARO
|
||||
uint32_t last_baro_update_ms;
|
||||
#endif
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
uint32_t last_airspeed_update_ms;
|
||||
#endif
|
||||
#ifdef HAL_PERIPH_ENABLE_GPS
|
||||
bool saw_gps_lock_once;
|
||||
#endif
|
||||
|
||||
static AP_Periph_FW *_singleton;
|
||||
|
||||
|
|
|
@ -8,6 +8,11 @@
|
|||
|
||||
#include <dronecan_msgs.h>
|
||||
|
||||
#ifndef AP_PERIPH_EFI_MAX_RATE
|
||||
// default to 2x the AP_Vehicle rate
|
||||
#define AP_PERIPH_EFI_MAX_RATE 100U
|
||||
#endif
|
||||
|
||||
/*
|
||||
update CAN EFI
|
||||
*/
|
||||
|
@ -16,6 +21,15 @@ void AP_Periph_FW::can_efi_update(void)
|
|||
if (!efi.enabled()) {
|
||||
return;
|
||||
}
|
||||
|
||||
#if AP_PERIPH_EFI_MAX_RATE > 0
|
||||
const uint32_t now_ms = AP_HAL::millis();
|
||||
if (now_ms - last_efi_update_ms < (1000U / AP_PERIPH_EFI_MAX_RATE)) {
|
||||
return;
|
||||
}
|
||||
last_efi_update_ms = now_ms;
|
||||
#endif
|
||||
|
||||
efi.update();
|
||||
const uint32_t update_ms = efi.get_last_update_ms();
|
||||
if (!efi.is_healthy() || efi_update_ms == update_ms) {
|
||||
|
|
Loading…
Reference in New Issue