mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Plane: fix acro stabilization check
This commit is contained in:
parent
4a7ce1b384
commit
aeaff72e14
@ -1869,11 +1869,6 @@ void QuadPlane::control_run(void)
|
|||||||
switch (plane.control_mode->mode_number()) {
|
switch (plane.control_mode->mode_number()) {
|
||||||
case Mode::Number::QACRO:
|
case Mode::Number::QACRO:
|
||||||
control_qacro();
|
control_qacro();
|
||||||
if (!is_tailsitter()) {
|
|
||||||
// also stabilize using fixed wing surfaces
|
|
||||||
plane.stabilize_acro(plane.get_speed_scaler());
|
|
||||||
}
|
|
||||||
return;
|
|
||||||
break;
|
break;
|
||||||
case Mode::Number::QSTABILIZE:
|
case Mode::Number::QSTABILIZE:
|
||||||
control_stabilize();
|
control_stabilize();
|
||||||
@ -1896,10 +1891,15 @@ void QuadPlane::control_run(void)
|
|||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// we also stabilize using fixed wing surfaces
|
// we also stabilize using fixed wing surfaces
|
||||||
float speed_scaler = plane.get_speed_scaler();
|
float speed_scaler = plane.get_speed_scaler();
|
||||||
plane.stabilize_roll(speed_scaler);
|
if (plane.control_mode->mode_number() == Mode::Number::QACRO) {
|
||||||
plane.stabilize_pitch(speed_scaler);
|
plane.stabilize_acro(speed_scaler);
|
||||||
|
} else {
|
||||||
|
plane.stabilize_roll(speed_scaler);
|
||||||
|
plane.stabilize_pitch(speed_scaler);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user