mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
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
030eab0f86
commit
ebe2278f5d
@ -370,7 +370,17 @@ void Plane::stabilize()
|
|||||||
nav_pitch_cd = constrain_float((quadplane.tailsitter.transition_angle+5)*100, 5500, 8500),
|
nav_pitch_cd = constrain_float((quadplane.tailsitter.transition_angle+5)*100, 5500, 8500),
|
||||||
nav_roll_cd = 0;
|
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 == &mode_training) {
|
if (control_mode == &mode_training) {
|
||||||
stabilize_training(speed_scaler);
|
stabilize_training(speed_scaler);
|
||||||
} else if (control_mode == &mode_acro) {
|
} else if (control_mode == &mode_acro) {
|
||||||
|
@ -349,6 +349,9 @@ private:
|
|||||||
// This is used to enable the inverted flight feature
|
// This is used to enable the inverted flight feature
|
||||||
bool inverted_flight;
|
bool inverted_flight;
|
||||||
|
|
||||||
|
// last time we ran roll/pitch stabilization
|
||||||
|
uint32_t last_stabilize_ms;
|
||||||
|
|
||||||
// Failsafe
|
// Failsafe
|
||||||
struct {
|
struct {
|
||||||
// Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold
|
// Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold
|
||||||
|
Loading…
Reference in New Issue
Block a user