mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Copter: run Linux boards at 100Hz for now
we should be able to do 400Hz in future
This commit is contained in:
parent
9e01c657e5
commit
a627cd2af2
@ -86,16 +86,11 @@
|
|||||||
# define AC_RALLY DISABLED
|
# define AC_RALLY DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
// low power CPUs (APM1, APM2 and SITL)
|
// low power CPUs (APM1, APM2 and SITL)
|
||||||
# define MAIN_LOOP_RATE 100
|
# define MAIN_LOOP_RATE 100
|
||||||
# define MAIN_LOOP_SECONDS 0.01
|
# define MAIN_LOOP_SECONDS 0.01
|
||||||
# define MAIN_LOOP_MICROS 10000
|
# define MAIN_LOOP_MICROS 10000
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
||||||
// Linux boards
|
|
||||||
# define MAIN_LOOP_RATE 200
|
|
||||||
# define MAIN_LOOP_SECONDS 0.005
|
|
||||||
# define MAIN_LOOP_MICROS 5000
|
|
||||||
#else
|
#else
|
||||||
// high power CPUs (Flymaple, PX4, Pixhawk, VRBrain)
|
// high power CPUs (Flymaple, PX4, Pixhawk, VRBrain)
|
||||||
# define MAIN_LOOP_RATE 400
|
# define MAIN_LOOP_RATE 400
|
||||||
|
Loading…
Reference in New Issue
Block a user