From 6729ee0709f9f0c9ec381b48d1eb9d4b4c092d6b Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 1 Jan 2025 17:06:12 +0000 Subject: [PATCH] AP_HAL: allow individual boards to define HAL_INS_RATE_LOOP allow fast rate loop on F4 with one IMU --- libraries/AP_HAL/board/chibios.h | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL/board/chibios.h b/libraries/AP_HAL/board/chibios.h index 9c51ac58ea9e0..69992f2b62034 100644 --- a/libraries/AP_HAL/board/chibios.h +++ b/libraries/AP_HAL/board/chibios.h @@ -141,8 +141,15 @@ #define HAL_USE_QUADSPI (HAL_USE_QUADSPI1 || HAL_USE_QUADSPI2) #define HAL_USE_OCTOSPI (HAL_USE_OCTOSPI1 || HAL_USE_OCTOSPI2) -#if defined(STM32H7) || defined(STM32F7) +#ifndef HAL_INS_RATE_LOOP +#if defined(STM32H7) || defined(STM32F7) || (defined(STM32F4) && INS_MAX_INSTANCES == 1) +/* F405 tested successfully with: + INS_GYRO_RATE = 1 (2kHz) + SCHED_LOOP_RATE = 200 + FSTRATE_DIV = 2 (1kHz) + SERVO_DSHOT_RATE = 1 (1kHz)*/ #define HAL_INS_RATE_LOOP 1 #else #define HAL_INS_RATE_LOOP 0 #endif +#endif