mirror of https://github.com/ArduPilot/ardupilot
Plane: changed default THR_MAX to 100
we have left it at 75 for far too long
This commit is contained in:
parent
4055869d7f
commit
48ae2f2de0
|
@ -288,7 +288,7 @@
|
|||
# define THROTTLE_CRUISE 45
|
||||
#endif
|
||||
#ifndef THROTTLE_MAX
|
||||
# define THROTTLE_MAX 75
|
||||
# define THROTTLE_MAX 100
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
Loading…
Reference in New Issue