mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Raised the Max throttle to 1000, min to 200. Worked good in SIM with Tridge's motor safety patch.
This commit is contained in:
parent
c9093a1609
commit
ee78818f5a
@ -441,10 +441,10 @@
|
|||||||
# define THROTTLE_FAILSAFE_ACTION 2
|
# define THROTTLE_FAILSAFE_ACTION 2
|
||||||
#endif
|
#endif
|
||||||
#ifndef MINIMUM_THROTTLE
|
#ifndef MINIMUM_THROTTLE
|
||||||
# define MINIMUM_THROTTLE 130
|
# define MINIMUM_THROTTLE 200
|
||||||
#endif
|
#endif
|
||||||
#ifndef MAXIMUM_THROTTLE
|
#ifndef MAXIMUM_THROTTLE
|
||||||
# define MAXIMUM_THROTTLE 850
|
# define MAXIMUM_THROTTLE 1000
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef AUTO_LAND_TIME
|
#ifndef AUTO_LAND_TIME
|
||||||
|
Loading…
Reference in New Issue
Block a user