mirror of https://github.com/ArduPilot/ardupilot
Copter: fixed drift mode
the throttle assistance gain also needs to be scaled by 1000x for new throttle range
This commit is contained in:
parent
f33cdaa212
commit
bd3a58a727
|
@ -14,7 +14,7 @@
|
|||
#endif
|
||||
|
||||
#ifndef DRIFT_THR_ASSIST_GAIN
|
||||
# define DRIFT_THR_ASSIST_GAIN 1.8f // gain controlling amount of throttle assistance
|
||||
# define DRIFT_THR_ASSIST_GAIN 0.0018f // gain controlling amount of throttle assistance
|
||||
#endif
|
||||
|
||||
#ifndef DRIFT_THR_ASSIST_MAX
|
||||
|
|
Loading…
Reference in New Issue