mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
Arducopter - Attitude.pde - fixed small bug in pitch stabilise
This commit is contained in:
parent
aaa0214ded
commit
68d1fa6ec7
@ -69,10 +69,7 @@ get_stabilize_pitch(int32_t target_angle)
|
|||||||
pitch_I = constrain(pitch_I, -120, 120); // +- 1200
|
pitch_I = constrain(pitch_I, -120, 120); // +- 1200
|
||||||
|
|
||||||
// conver to desired Rate:
|
// conver to desired Rate:
|
||||||
rate = g.pi_stabilize_roll.get_p(error + pitch_I);
|
rate = g.pi_stabilize_pitch.get_p(error + pitch_I);
|
||||||
|
|
||||||
// convert to desired Rate:
|
|
||||||
rate = g.pi_stabilize_pitch.get_p(error);
|
|
||||||
|
|
||||||
// experiment to pipe iterm directly into the output
|
// experiment to pipe iterm directly into the output
|
||||||
int16_t iterm = g.pi_stabilize_pitch.get_i(error, G_Dt);
|
int16_t iterm = g.pi_stabilize_pitch.get_i(error, G_Dt);
|
||||||
|
Loading…
Reference in New Issue
Block a user