mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APM_Control: Fix typos
This commit is contained in:
parent
3033c53834
commit
8d6cc587c5
@ -90,7 +90,7 @@ AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type,
|
||||
auto-tuning table. This table gives the starting values for key
|
||||
tuning parameters based on a user chosen AUTOTUNE_LEVEL parameter
|
||||
from 1 to 10. Level 1 is a very soft tune. Level 10 is a very
|
||||
agressive tune.
|
||||
aggressive tune.
|
||||
*/
|
||||
static const struct {
|
||||
float tau;
|
||||
|
@ -163,7 +163,7 @@ additional values that anbe set by more advanced users.
|
||||
2) If you get porposising and the response is still too sluggish, increase
|
||||
the CTL_RLL_K_D gain in small increments of 0.01 until the overshoot or
|
||||
porpoise goes away. If it hasn't worked by the time you have reached a
|
||||
value of 0.1 for CTL_PTCH_K_D, DONT go any further until you have checked
|
||||
value of 0.1 for CTL_PTCH_K_D, DON'T go any further until you have checked
|
||||
your servo temperatures immediately after landing as in extreme
|
||||
cases turning up this gain can cause rapid servo movement and overheat
|
||||
the servos leading to premature failure.
|
||||
|
Loading…
Reference in New Issue
Block a user