AP_HAL: set HAL_INS_RATE_LOOP in boards

restrict rate loop to H7 and F7
This commit is contained in:
Andy Piper 2024-06-22 20:00:44 +01:00 committed by Andrew Tridgell
parent c4ab8e25c4
commit 76897e9674
4 changed files with 18 additions and 0 deletions

View File

@ -385,4 +385,8 @@
#define HAL_WITH_POSTYPE_DOUBLE BOARD_FLASH_SIZE > 1024
#endif
#ifndef HAL_INS_RATE_LOOP
#define HAL_INS_RATE_LOOP 0
#endif
#define HAL_GPIO_LED_OFF (!HAL_GPIO_LED_ON)

View File

@ -140,3 +140,9 @@
#endif
#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)
#define HAL_INS_RATE_LOOP 1
#else
#define HAL_INS_RATE_LOOP 0
#endif

View File

@ -422,3 +422,7 @@
#else
#define HAL_LINUX_USE_VIRTUAL_CAN 0
#endif
#ifndef HAL_INS_RATE_LOOP
#define HAL_INS_RATE_LOOP 1
#endif

View File

@ -96,3 +96,7 @@
#endif
#define HAL_SOLO_GIMBAL_ENABLED 1
#ifndef HAL_INS_RATE_LOOP
#define HAL_INS_RATE_LOOP 1
#endif