void Copter::read_radio() { uint32_t tnow_ms = millis(); if (hal.rcin->new_input()) { ap.new_radio_frame = true; RC_Channel::set_pwm_all(); set_throttle_and_failsafe(channel_throttle->get_radio_in()); set_throttle_zero_flag(channel_throttle->get_control_in()); // flag we must have an rc receiver attached if (!failsafe.rc_override_active) { ap.rc_receiver_present = true; } // update output on any aux channels, for manual passthru RC_Channel_aux::output_ch_all(); // pass pilot input through to motors (used to allow wiggling servos while disarmed on heli, single, coax copters) radio_passthrough_to_motors(); float dt = (tnow_ms - last_radio_update_ms)*1.0e-3f; rc_throttle_control_in_filter.apply(g.rc_3.get_control_in(), dt); last_radio_update_ms = tnow_ms; }else{ uint32_t elapsed = tnow_ms - last_radio_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 && (ap.rc_receiver_present||motors.armed()) && !failsafe.radio)) { Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME); set_failsafe_radio(true); } } }
void Copter::read_radio() { static uint32_t last_update_ms = 0; uint32_t tnow_ms = millis(); if (hal.rcin->new_input()) { last_update_ms = tnow_ms; ap.new_radio_frame = true; RC_Channel::set_pwm_all(); set_throttle_and_failsafe(channel_throttle->radio_in); set_throttle_zero_flag(channel_throttle->control_in); // flag we must have an rc receiver attached if (!failsafe.rc_override_active) { ap.rc_receiver_present = true; } // update output on any aux channels, for manual passthru RC_Channel_aux::output_ch_all(); }else{ 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 && (ap.rc_receiver_present||motors.armed()) && !failsafe.radio)) { Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME); set_failsafe_radio(true); } } }
void Copter::read_radio() { const uint32_t tnow_ms = millis(); if (rc().read_input()) { ap.new_radio_frame = true; set_throttle_and_failsafe(channel_throttle->get_radio_in()); set_throttle_zero_flag(channel_throttle->get_control_in()); if (!ap.rc_receiver_present) { // RC receiver must be attached if we've just got input and // there are no overrides ap.rc_receiver_present = !RC_Channels::has_active_overrides(); } // pass pilot input through to motors (used to allow wiggling servos while disarmed on heli, single, coax copters) radio_passthrough_to_motors(); const float dt = (tnow_ms - last_radio_update_ms)*1.0e-3f; rc_throttle_control_in_filter.apply(channel_throttle->get_control_in(), dt); last_radio_update_ms = tnow_ms; return; } // No radio input this time if (failsafe.radio) { // already in failsafe! return; } const uint32_t elapsed = tnow_ms - last_radio_update_ms; // turn on throttle failsafe if no update from the RC Radio for 500ms or 2000ms if we are using RC_OVERRIDE const uint32_t timeout = RC_Channels::has_active_overrides() ? FS_RADIO_RC_OVERRIDE_TIMEOUT_MS : FS_RADIO_TIMEOUT_MS; if (elapsed < timeout) { // not timed out yet return; } if (!g.failsafe_throttle) { // throttle failsafe not enabled return; } if (!ap.rc_receiver_present && !motors->armed()) { // we only failsafe if we are armed OR we have ever seen an RC receiver return; } // Nobody ever talks to us. Log an error and enter failsafe. Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME); set_failsafe_radio(true); }