added a constraint to D term

This commit is contained in:
Jason Short 2012-02-23 09:14:27 -08:00
parent e3c3307c09
commit 364afe8da0
1 changed files with 2 additions and 0 deletions

View File

@ -134,6 +134,7 @@ get_rate_roll(int32_t target_rate)
// MultiWii uses a filter of the last three to get around noise and get a stronger signal.
// Works well! Thanks!
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d;
d_temp = constrain(d_temp, -400, 400);
target_rate -= d_temp;
// output control:
@ -167,6 +168,7 @@ get_rate_pitch(int32_t target_rate)
// D term
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d;
d_temp = constrain(d_temp, -400, 400);
target_rate -= d_temp;
// output control: