mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: remove check for AVR CPUs
Remove the checks for HAL_CPU_CLASS > HAL_CPU_CLASS_16 and HAL_CPU_CLASS >= HAL_CPU_CLASS_75. Corresponding dead code will be removed on separate commits.
This commit is contained in:
parent
fb28f426da
commit
ca4ae1c9e0
|
@ -26,7 +26,7 @@
|
|||
#define AP_MOTORS_THR_MIX_MAX_DEFAULT 0.5f // maximum throttle mix default
|
||||
|
||||
// To-Do: replace this hard coded counter with a timer
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
#if 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