mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: fix Ch6 Tuning when no RC Receiver on boot
This commit is contained in:
parent
93fc595d4d
commit
e2879b375d
@ -11,8 +11,8 @@
|
||||
// should be called at 3.3hz
|
||||
void Copter::tuning() {
|
||||
|
||||
// exit immediately if not tuning of when radio failsafe is invoked so tuning values are not set to zero
|
||||
if ((g.radio_tuning <= 0) || failsafe.radio || failsafe.radio_counter != 0) {
|
||||
// exit immediately if not using tuning function, or when radio failsafe is invoked, so tuning values are not set to zero
|
||||
if ((g.radio_tuning <= 0) || failsafe.radio || failsafe.radio_counter != 0 || g.rc_6.radio_in == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user