mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: set HAL_INS_RATE_LOOP in boards
restrict rate loop to H7 and F7
This commit is contained in:
parent
c4ab8e25c4
commit
76897e9674
|
@ -385,4 +385,8 @@
|
||||||
#define HAL_WITH_POSTYPE_DOUBLE BOARD_FLASH_SIZE > 1024
|
#define HAL_WITH_POSTYPE_DOUBLE BOARD_FLASH_SIZE > 1024
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef HAL_INS_RATE_LOOP
|
||||||
|
#define HAL_INS_RATE_LOOP 0
|
||||||
|
#endif
|
||||||
|
|
||||||
#define HAL_GPIO_LED_OFF (!HAL_GPIO_LED_ON)
|
#define HAL_GPIO_LED_OFF (!HAL_GPIO_LED_ON)
|
||||||
|
|
|
@ -140,3 +140,9 @@
|
||||||
#endif
|
#endif
|
||||||
#define HAL_USE_QUADSPI (HAL_USE_QUADSPI1 || HAL_USE_QUADSPI2)
|
#define HAL_USE_QUADSPI (HAL_USE_QUADSPI1 || HAL_USE_QUADSPI2)
|
||||||
#define HAL_USE_OCTOSPI (HAL_USE_OCTOSPI1 || HAL_USE_OCTOSPI2)
|
#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
|
||||||
|
|
|
@ -422,3 +422,7 @@
|
||||||
#else
|
#else
|
||||||
#define HAL_LINUX_USE_VIRTUAL_CAN 0
|
#define HAL_LINUX_USE_VIRTUAL_CAN 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef HAL_INS_RATE_LOOP
|
||||||
|
#define HAL_INS_RATE_LOOP 1
|
||||||
|
#endif
|
||||||
|
|
|
@ -96,3 +96,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define HAL_SOLO_GIMBAL_ENABLED 1
|
#define HAL_SOLO_GIMBAL_ENABLED 1
|
||||||
|
|
||||||
|
#ifndef HAL_INS_RATE_LOOP
|
||||||
|
#define HAL_INS_RATE_LOOP 1
|
||||||
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue