mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AP_HAL: allow individual boards to define HAL_INS_RATE_LOOP
allow fast rate loop on F4 with one IMU
This commit is contained in:
parent
01345e5a38
commit
2b46f5a20b
@ -141,8 +141,17 @@
|
||||
#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) \
|
||||
&& defined(INS_MAX_INSTANCES) && INS_MAX_INSTANCES == 1)
|
||||
/* F405 tested successfully with:
|
||||
INS_GYRO_RATE = 1 (2kHz)
|
||||
SCHED_LOOP_RATE = 200
|
||||
FSTRATE_DIV = 2 (1kHz)
|
||||
FSTRATE_ENABLE = 1
|
||||
SERVO_DSHOT_RATE = 1 (1kHz)*/
|
||||
#define HAL_INS_RATE_LOOP 1
|
||||
#else
|
||||
#define HAL_INS_RATE_LOOP 0
|
||||
#endif
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user