Skip to content

Commit 69a5f8c

Browse files
committed
Copter: tidy radio throttle failsafe code
1 parent 39ac45a commit 69a5f8c

File tree

1 file changed

+6
-3
lines changed

1 file changed

+6
-3
lines changed

ArduCopter/radio.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -133,9 +133,12 @@ void Copter::set_throttle_and_failsafe(uint16_t throttle_pwm)
133133

134134
//check for low throttle value
135135
if (throttle_pwm < (uint16_t)g.failsafe_throttle_value) {
136-
137-
// if we are already in failsafe or motors not armed pass through throttle and exit
138-
if (failsafe.radio || !(rc().has_ever_seen_rc_input() || motors->armed())) {
136+
if (failsafe.radio) {
137+
// already in failsafe, and we should stay there
138+
return;
139+
}
140+
if (!rc().has_ever_seen_rc_input()) {
141+
// do not failsafe if we have never seen RC
139142
return;
140143
}
141144

0 commit comments

Comments
 (0)