diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 1d4e39e985..08333da789 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -342,7 +342,7 @@ private: uint8_t in_arming_delay : 1; // 24 // true while we are armed but waiting to spin motors uint8_t initialised_params : 1; // 25 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done uint8_t compass_init_location : 1; // 26 // true when the compass's initial location has been set - uint8_t rc_override_enable : 1; // 27 // aux switch rc_override is allowed + uint8_t unused2 : 1; // 27 // aux switch rc_override is allowed uint8_t armed_with_switch : 1; // 28 // we armed using a arming switch }; uint32_t value; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 66313774d3..4d0156a947 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1052,7 +1052,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) if(msg->sysid != copter.g.sysid_my_gcs) { break; // Only accept control from our gcs } - if (!copter.ap.rc_override_enable) { + if (!rc().gcs_overrides_enabled()) { if (copter.failsafe.rc_override_active) { // if overrides were active previously, disable them copter.failsafe.rc_override_active = false; RC_Channels::clear_overrides(); diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index cdcbfe9728..5deb3587ce 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -81,7 +81,6 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const aux_ case AVOID_PROXIMITY: case INVERTED: case WINCH_ENABLE: - case RC_OVERRIDE_ENABLE: do_aux_function(ch_option, ch_flag); break; // the following functions do not need to be initialised: @@ -512,23 +511,6 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw #endif break; - case RC_OVERRIDE_ENABLE: - // Allow or disallow RC_Override - switch (ch_flag) { - case HIGH: { - copter.ap.rc_override_enable = true; - break; - } - case MIDDLE: - // nothing - break; - case LOW: { - copter.ap.rc_override_enable = false; - break; - } - } - break; - #ifdef USERHOOK_AUXSWITCH case USER_FUNC1: userhook_auxSwitch1(ch_flag); diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index f1cbe6069e..89db9527f1 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -43,9 +43,6 @@ void Copter::init_rc_in() // initialise throttle_zero flag ap.throttle_zero = true; - - // Allow override by default at start - ap.rc_override_enable = true; } // init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 2b12dc167b..2939bb791e 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -275,9 +275,6 @@ void Copter::init_ardupilot() // disable safety if requested BoardConfig.init_safety(); - // default enable RC override - copter.ap.rc_override_enable = true; - hal.console->printf("\nReady to FLY "); // flag that initialisation has completed