mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
lowered Loiter I, commented out unused var
This commit is contained in:
parent
c02b403a06
commit
95ac9d163e
@ -166,7 +166,7 @@ static int16_t
|
||||
get_nav_throttle(int32_t z_error)
|
||||
{
|
||||
static int16_t old_output = 0;
|
||||
static int16_t rate_d = 0;
|
||||
//static int16_t rate_d = 0;
|
||||
|
||||
int16_t rate_error;
|
||||
int16_t output;
|
||||
|
@ -614,7 +614,7 @@
|
||||
# define LOITER_P 2.0 // was .25 in previous
|
||||
#endif
|
||||
#ifndef LOITER_I
|
||||
# define LOITER_I 0.05 // Wind control
|
||||
# define LOITER_I 0.04 // Wind control
|
||||
#endif
|
||||
#ifndef LOITER_IMAX
|
||||
# define LOITER_IMAX 30 // degrees°
|
||||
|
Loading…
Reference in New Issue
Block a user