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