mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
ArduPlane: Fix throttle nudge reset due to wrong radio timing
This commit is contained in:
parent
f0d8ca5e37
commit
a7c0495e07
@ -179,8 +179,6 @@ void Plane::read_radio()
|
|||||||
{
|
{
|
||||||
if (!rc().read_input()) {
|
if (!rc().read_input()) {
|
||||||
control_failsafe();
|
control_failsafe();
|
||||||
airspeed_nudge_cm = 0;
|
|
||||||
throttle_nudge = 0;
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -262,6 +260,9 @@ void Plane::control_failsafe()
|
|||||||
channel_pitch->set_control_in(0);
|
channel_pitch->set_control_in(0);
|
||||||
channel_rudder->set_control_in(0);
|
channel_rudder->set_control_in(0);
|
||||||
|
|
||||||
|
airspeed_nudge_cm = 0;
|
||||||
|
throttle_nudge = 0;
|
||||||
|
|
||||||
switch (control_mode->mode_number()) {
|
switch (control_mode->mode_number()) {
|
||||||
case Mode::Number::QSTABILIZE:
|
case Mode::Number::QSTABILIZE:
|
||||||
case Mode::Number::QHOVER:
|
case Mode::Number::QHOVER:
|
||||||
|
Loading…
Reference in New Issue
Block a user