Skip to content

Commit

Permalink
AP_HAL: allow individual boards to define HAL_INS_RATE_LOOP
Browse files Browse the repository at this point in the history
allow fast rate loop on F4 with one IMU
  • Loading branch information
andyp1per committed Jan 1, 2025
1 parent 5726c03 commit 6729ee0
Showing 1 changed file with 8 additions and 1 deletion.
9 changes: 8 additions & 1 deletion libraries/AP_HAL/board/chibios.h
Original file line number Diff line number Diff line change
Expand Up @@ -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

0 comments on commit 6729ee0

Please sign in to comment.