mirror of https://github.com/ArduPilot/ardupilot
slightly less filtering for less latency
This commit is contained in:
parent
275815a7c9
commit
02d6adb21f
|
@ -165,7 +165,8 @@ get_nav_throttle(int32_t z_error)
|
|||
//output -= constrain(rate_d, -25, 25);
|
||||
|
||||
// light filter of output
|
||||
output = (old_output * 3 + output) / 4;
|
||||
//output = (old_output * 3 + output) / 4;
|
||||
output = (old_output + output) / 2;
|
||||
|
||||
// save our output
|
||||
old_output = output;
|
||||
|
|
Loading…
Reference in New Issue