added a constraint to D term
This commit is contained in:
parent
e88e6200b4
commit
b1340bbf80
@ -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.
|
// MultiWii uses a filter of the last three to get around noise and get a stronger signal.
|
||||||
// Works well! Thanks!
|
// Works well! Thanks!
|
||||||
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d;
|
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d;
|
||||||
|
d_temp = constrain(d_temp, -400, 400);
|
||||||
target_rate -= d_temp;
|
target_rate -= d_temp;
|
||||||
|
|
||||||
// output control:
|
// output control:
|
||||||
@ -167,6 +168,7 @@ get_rate_pitch(int32_t target_rate)
|
|||||||
|
|
||||||
// D term
|
// D term
|
||||||
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d;
|
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d;
|
||||||
|
d_temp = constrain(d_temp, -400, 400);
|
||||||
target_rate -= d_temp;
|
target_rate -= d_temp;
|
||||||
|
|
||||||
// output control:
|
// output control:
|
||||||
|
Loading…
Reference in New Issue
Block a user