mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Sub: Remove RC radio failsafe
This commit is contained in:
parent
23122f4b90
commit
9ec79ab654
@ -57,33 +57,6 @@ void Sub::set_simple_mode(uint8_t b)
|
||||
}
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
void Sub::set_failsafe_radio(bool b)
|
||||
{
|
||||
// only act on changes
|
||||
// -------------------
|
||||
if(failsafe.radio != b) {
|
||||
|
||||
// store the value so we don't trip the gate twice
|
||||
// -----------------------------------------------
|
||||
failsafe.radio = b;
|
||||
|
||||
if (failsafe.radio == false) {
|
||||
// We've regained radio contact
|
||||
// ----------------------------
|
||||
failsafe_radio_off_event();
|
||||
}else{
|
||||
// We've lost radio contact
|
||||
// ------------------------
|
||||
failsafe_radio_on_event();
|
||||
}
|
||||
|
||||
// update AP_Notify
|
||||
AP_Notify::flags.failsafe_radio = b;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// ---------------------------------------------
|
||||
void Sub::set_failsafe_battery(bool b)
|
||||
{
|
||||
|
@ -222,22 +222,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @User: Standard
|
||||
GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),
|
||||
|
||||
// @Param: FS_THR_ENABLE
|
||||
// @DisplayName: Throttle Failsafe Enable
|
||||
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
|
||||
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always LAND
|
||||
// @User: Standard
|
||||
GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_DISABLED),
|
||||
|
||||
// @Param: FS_THR_VALUE
|
||||
// @DisplayName: Throttle Failsafe Value
|
||||
// @Description: The PWM level on channel 3 below which throttle sailsafe triggers
|
||||
// @Range: 925 1100
|
||||
// @Units: pwm
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
|
||||
|
||||
// @Param: THR_DZ
|
||||
// @DisplayName: Throttle deadzone
|
||||
// @Description: The deadzone above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes
|
||||
|
@ -182,8 +182,6 @@ public:
|
||||
k_param_failsafe_battery_enabled,
|
||||
k_param_fs_batt_mah,
|
||||
k_param_fs_batt_voltage,
|
||||
k_param_failsafe_throttle,
|
||||
k_param_failsafe_throttle_value,
|
||||
|
||||
|
||||
// Misc Sub settings
|
||||
@ -286,8 +284,6 @@ public:
|
||||
|
||||
// Throttle
|
||||
//
|
||||
AP_Int8 failsafe_throttle;
|
||||
AP_Int16 failsafe_throttle_value;
|
||||
AP_Int16 throttle_deadzone;
|
||||
|
||||
// Flight modes
|
||||
|
@ -288,8 +288,6 @@ private:
|
||||
uint32_t last_leak_warn_ms; // last time a leak warning was sent to gcs
|
||||
uint32_t last_gcs_warn_ms;
|
||||
|
||||
int8_t radio_counter; // number of iterations with throttle below throttle_fs_value
|
||||
|
||||
uint32_t last_heartbeat_ms; // the time when the last HEARTBEAT message arrived from a GCS - used for triggering gcs failsafe
|
||||
uint32_t terrain_first_failure_ms; // the first time terrain data access failed - used to calculate the duration of the failure
|
||||
uint32_t terrain_last_failure_ms; // the most recent time terrain data access failed
|
||||
@ -522,7 +520,6 @@ private:
|
||||
bool home_is_set();
|
||||
void set_auto_armed(bool b);
|
||||
void set_simple_mode(uint8_t b);
|
||||
void set_failsafe_radio(bool b);
|
||||
void set_failsafe_battery(bool b);
|
||||
void set_pre_arm_check(bool b);
|
||||
void set_pre_arm_rc_check(bool b);
|
||||
@ -708,8 +705,6 @@ private:
|
||||
void esc_calibration_passthrough();
|
||||
void esc_calibration_auto();
|
||||
bool should_disarm_on_failsafe();
|
||||
void failsafe_radio_on_event();
|
||||
void failsafe_radio_off_event();
|
||||
void failsafe_battery_event(void);
|
||||
void failsafe_gcs_check();
|
||||
void failsafe_terrain_check();
|
||||
@ -784,7 +779,6 @@ private:
|
||||
void handle_jsbutton_press(uint8_t button,bool shift=false,bool held=false);
|
||||
void camera_tilt_smooth();
|
||||
JSButton* get_button(uint8_t index);
|
||||
void set_throttle_and_failsafe(uint16_t throttle_pwm);
|
||||
void set_throttle_zero_flag(int16_t throttle_control);
|
||||
void radio_passthrough_to_motors();
|
||||
void init_barometer(bool full_calibration);
|
||||
|
@ -98,8 +98,7 @@ uint8_t Sub::mavlink_compassmot(mavlink_channel_t chan)
|
||||
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Throttle");
|
||||
}
|
||||
|
||||
// disable throttle and battery failsafe
|
||||
g.failsafe_throttle = FS_THR_DISABLED;
|
||||
// disable battery failsafe
|
||||
g.failsafe_battery_enabled = FS_BATT_DISABLED;
|
||||
|
||||
// disable motor compensation
|
||||
@ -256,7 +255,6 @@ uint8_t Sub::mavlink_compassmot(mavlink_channel_t chan)
|
||||
failsafe_enable();
|
||||
|
||||
// re-enable failsafes
|
||||
g.failsafe_throttle.load();
|
||||
g.failsafe_battery_enabled.load();
|
||||
|
||||
// flag we have completed
|
||||
|
@ -2,48 +2,6 @@
|
||||
|
||||
#include "Sub.h"
|
||||
|
||||
/*
|
||||
* This event will be called when the failsafe changes
|
||||
* boolean failsafe reflects the current state
|
||||
*/
|
||||
void Sub::failsafe_radio_on_event()
|
||||
{
|
||||
// // if motors are not armed there is nothing to do
|
||||
// if( !motors.armed() ) {
|
||||
// return;
|
||||
// }
|
||||
//
|
||||
// if (should_disarm_on_failsafe()) {
|
||||
// init_disarm_motors();
|
||||
// } else {
|
||||
// if (control_mode == AUTO && g.failsafe_throttle == FS_THR_ENABLED_CONTINUE_MISSION) {
|
||||
// // continue mission
|
||||
// } else if (control_mode == LAND && g.failsafe_battery_enabled == FS_BATT_LAND && failsafe.battery) {
|
||||
// // continue landing
|
||||
// } else {
|
||||
// if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_LAND) {
|
||||
// set_mode_land_with_pause(MODE_REASON_RADIO_FAILSAFE);
|
||||
// } else {
|
||||
// set_mode_RTL_or_land_with_pause(MODE_REASON_RADIO_FAILSAFE);
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
//
|
||||
// // log the error to the dataflash
|
||||
// Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_RADIO, ERROR_CODE_FAILSAFE_OCCURRED);
|
||||
|
||||
}
|
||||
|
||||
// failsafe_off_event - respond to radio contact being regained
|
||||
// we must be in AUTO, LAND or RTL modes
|
||||
// or Stabilize or ACRO mode but with motors disarmed
|
||||
void Sub::failsafe_radio_off_event()
|
||||
{
|
||||
// no need to do anything except log the error as resolved
|
||||
// user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_RADIO, ERROR_CODE_FAILSAFE_RESOLVED);
|
||||
}
|
||||
|
||||
void Sub::failsafe_battery_event(void)
|
||||
{
|
||||
// // return immediately if low battery event has already been triggered
|
||||
|
@ -112,7 +112,6 @@ uint8_t Sub::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq,
|
||||
}
|
||||
|
||||
// disable throttle, battery and gps failsafe
|
||||
g.failsafe_throttle = FS_THR_DISABLED;
|
||||
g.failsafe_battery_enabled = FS_BATT_DISABLED;
|
||||
g.failsafe_gcs = FS_GCS_DISABLED;
|
||||
|
||||
@ -153,7 +152,6 @@ void Sub::motor_test_stop()
|
||||
motor_test_timeout_ms = 0;
|
||||
|
||||
// re-enable failsafes
|
||||
g.failsafe_throttle.load();
|
||||
g.failsafe_battery_enabled.load();
|
||||
g.failsafe_gcs.load();
|
||||
|
||||
|
@ -125,7 +125,7 @@ void Sub::read_aux_switches()
|
||||
uint8_t switch_position;
|
||||
|
||||
// exit immediately during radio failsafe
|
||||
if (failsafe.radio || failsafe.radio_counter != 0) {
|
||||
if (failsafe.radio) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user