mirror of https://github.com/ArduPilot/ardupilot
Plane: reset rate controller integrators if not run for 2s
this prevents a bug where integrator buildup can happen from a previous flight mode
This commit is contained in:
parent
f0a02bb6ba
commit
f5bf610b9a
|
@ -384,7 +384,17 @@ void Plane::stabilize()
|
|||
nav_pitch_cd = constrain_float((quadplane.tailsitter.transition_angle+5)*100, 5500, 8500),
|
||||
nav_roll_cd = 0;
|
||||
}
|
||||
|
||||
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (now - last_stabilize_ms > 2000) {
|
||||
// if we haven't run the rate controllers for 2 seconds then
|
||||
// reset the integrators
|
||||
rollController.reset_I();
|
||||
pitchController.reset_I();
|
||||
yawController.reset_I();
|
||||
}
|
||||
last_stabilize_ms = now;
|
||||
|
||||
if (control_mode == TRAINING) {
|
||||
stabilize_training(speed_scaler);
|
||||
} else if (control_mode == ACRO) {
|
||||
|
|
|
@ -313,6 +313,9 @@ private:
|
|||
// This is used to enable the PX4IO override for testing
|
||||
bool px4io_override_enabled;
|
||||
|
||||
// last time we ran roll/pitch stabilization
|
||||
uint32_t last_stabilize_ms;
|
||||
|
||||
// Failsafe
|
||||
struct {
|
||||
// Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold
|
||||
|
|
Loading…
Reference in New Issue