Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Allow individual boards to define HAL_INS_RATE_LOOP and enable on F4 with one IMU #28984

Merged
merged 1 commit into from
Jan 7, 2025
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 10 additions & 1 deletion libraries/AP_HAL/board/chibios.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
andyp1per marked this conversation as resolved.
Show resolved Hide resolved
/* F405 tested successfully with:
INS_GYRO_RATE = 1 (2kHz)
SCHED_LOOP_RATE = 200
FSTRATE_DIV = 2 (1kHz)
andyp1per marked this conversation as resolved.
Show resolved Hide resolved
FSTRATE_ENABLE = 1
SERVO_DSHOT_RATE = 1 (1kHz)*/
#define HAL_INS_RATE_LOOP 1
#else
#define HAL_INS_RATE_LOOP 0
#endif
#endif
Loading