mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
ACM: removed the experiment for rate error.
This commit is contained in:
parent
0ccfdc664d
commit
285f2dd791
@ -204,8 +204,8 @@ get_nav_throttle(int32_t z_error)
|
|||||||
rate_error = rate_error - climb_rate;
|
rate_error = rate_error - climb_rate;
|
||||||
|
|
||||||
// hack to see if we can smooth out oscillations
|
// hack to see if we can smooth out oscillations
|
||||||
if(rate_error < 0)
|
//if(rate_error < 0)
|
||||||
rate_error = rate_error >> 1;
|
// rate_error = rate_error >> 1;
|
||||||
|
|
||||||
// limit the rate
|
// limit the rate
|
||||||
output = constrain(g.pid_throttle.get_pid(rate_error, .02), -80, 120);
|
output = constrain(g.pid_throttle.get_pid(rate_error, .02), -80, 120);
|
||||||
|
Loading…
Reference in New Issue
Block a user