Skip to content

Commit

Permalink
Copter: allow radio failsafe while disarmed so that user can be notified
Browse files Browse the repository at this point in the history
  • Loading branch information
jschall authored and rmackay9 committed Dec 15, 2014
1 parent 21beb26 commit cafb38e
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ArduCopter/radio.pde
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ static void read_radio()
uint32_t elapsed = tnow_ms - last_update_ms;
// turn on throttle failsafe if no update from the RC Radio for 500ms or 2000ms if we are using RC_OVERRIDE
if (((!failsafe.rc_override_active && (elapsed >= FS_RADIO_TIMEOUT_MS)) || (failsafe.rc_override_active && (elapsed >= FS_RADIO_RC_OVERRIDE_TIMEOUT_MS))) &&
(g.failsafe_throttle && motors.armed() && !failsafe.radio)) {
(g.failsafe_throttle && (ap.rc_receiver_present||motors.armed()) && !failsafe.radio)) {
Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME);
set_failsafe_radio(true);
}
Expand All @@ -142,7 +142,7 @@ static void set_throttle_and_failsafe(uint16_t throttle_pwm)
if (throttle_pwm < (uint16_t)g.failsafe_throttle_value) {

// if we are already in failsafe or motors not armed pass through throttle and exit
if (failsafe.radio || !motors.armed()) {
if (failsafe.radio || !(ap.rc_receiver_present || motors.armed())) {
g.rc_3.set_pwm(throttle_pwm);
return;
}
Expand Down

0 comments on commit cafb38e

Please sign in to comment.