mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: default Loiter Pos P to 0.8 (was 0.2)
This commit is contained in:
parent
93e22ad6a4
commit
a2ea053c90
@ -7,7 +7,7 @@ Improvements over 3.0.1-rc1
|
||||
a) double flash arming light when pre-arm checks fail
|
||||
b) relax mag field checks to 35% min, 165% max of expected field
|
||||
3) loiter and auto changes:
|
||||
a) reduced Loiter Pos P to 0.2 (was 1.0)
|
||||
a) reduced Loiter Pos P to 0.8 (was 1.0)
|
||||
b) reduced Loiter speed to 5 m/s
|
||||
c) reduced WP_ACCEL to 1 m/s/s (was 250 m/s/s)
|
||||
d) rounding error fix in loiter controller
|
||||
|
@ -873,7 +873,7 @@
|
||||
// Loiter position control gains
|
||||
//
|
||||
#ifndef LOITER_P
|
||||
# define LOITER_P 0.2f
|
||||
# define LOITER_P 0.8f
|
||||
#endif
|
||||
#ifndef LOITER_I
|
||||
# define LOITER_I 0.0f
|
||||
|
Loading…
Reference in New Issue
Block a user