mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_Motors: fix for HAL_SITL rename
This commit is contained in:
parent
0c142bb25a
commit
2e57c62ebb
@ -72,7 +72,7 @@
|
||||
#define AP_MOTOR_ANY_LIMIT 0xFF
|
||||
|
||||
// To-Do: replace this hard coded counter with a timer
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
// slow start increments - throttle increase per (100hz) iteration. i.e. 5 = full speed in 2 seconds
|
||||
#define AP_MOTOR_SLOW_START_INCREMENT 10 // max throttle ramp speed (i.e. motors can reach full throttle in 1 second)
|
||||
#define AP_MOTOR_SLOW_START_LOW_END_INCREMENT 2 // min throttle ramp speed (i.e. motors will speed up from zero to _spin_when_armed speed in about 1 second)
|
||||
|
Loading…
Reference in New Issue
Block a user