mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
limiting alt hold rate error to 1m/s
This commit is contained in:
parent
370d633f51
commit
c855c81d2a
@ -130,7 +130,6 @@ get_rate_yaw(int32_t target_rate)
|
|||||||
return constrain(target_rate, -yaw_limit, yaw_limit);
|
return constrain(target_rate, -yaw_limit, yaw_limit);
|
||||||
}
|
}
|
||||||
|
|
||||||
#define ALT_ERROR_MAX 400
|
|
||||||
static int16_t
|
static int16_t
|
||||||
get_nav_throttle(int32_t z_error)
|
get_nav_throttle(int32_t z_error)
|
||||||
{
|
{
|
||||||
@ -138,11 +137,12 @@ get_nav_throttle(int32_t z_error)
|
|||||||
int16_t rate_error = 0;
|
int16_t rate_error = 0;
|
||||||
int16_t output = 0;
|
int16_t output = 0;
|
||||||
|
|
||||||
// limit error to prevent I term run up
|
|
||||||
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
|
|
||||||
|
|
||||||
// convert to desired Rate:
|
// convert to desired Rate:
|
||||||
rate_error = g.pi_alt_hold.get_p(z_error); //_p = .85
|
rate_error = g.pi_alt_hold.get_p(z_error);
|
||||||
|
rate_error = constrain(rate_error, -100, 100);
|
||||||
|
|
||||||
|
// limit error to prevent I term wind up
|
||||||
|
z_error = constrain(z_error, -400, 400);
|
||||||
|
|
||||||
// compensates throttle setpoint error for hovering
|
// compensates throttle setpoint error for hovering
|
||||||
int16_t iterm = g.pi_alt_hold.get_i(z_error, .1);
|
int16_t iterm = g.pi_alt_hold.get_i(z_error, .1);
|
||||||
|
Loading…
Reference in New Issue
Block a user