From 8d2f2443a2391a5b63c2a035f879699df9742b89 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 24 May 2020 12:26:00 +0100 Subject: [PATCH] Copter: add air mode aux function --- ArduCopter/Copter.h | 2 ++ ArduCopter/RC_Channel.cpp | 14 ++++++++++++++ ArduCopter/defines.h | 7 +++++++ ArduCopter/land_detector.cpp | 2 +- ArduCopter/radio.cpp | 2 +- 5 files changed, 25 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 50f5349700..e642263997 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -374,6 +374,8 @@ private: ap_t ap; + AirMode air_mode; // air mode is 0 = not-configured ; 1 = disabled; 2 = enabled + static_assert(sizeof(uint32_t) == sizeof(ap), "ap_t must be uint32_t"); // This is the state of the flight control system diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index 7c1b6c0afa..16332e2421 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -112,6 +112,7 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const AuxS case AUX_FUNC::SUPERSIMPLE_MODE: case AUX_FUNC::SURFACE_TRACKING: case AUX_FUNC::WINCH_ENABLE: + case AUX_FUNC::AIRMODE: do_aux_function(ch_option, ch_flag); break; default: @@ -593,6 +594,19 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi } #endif break; + + case AUX_FUNC::AIRMODE: + switch (ch_flag) { + case AuxSwitchPos::HIGH: + copter.air_mode = AirMode::AIRMODE_ENABLED; + break; + case AuxSwitchPos::MIDDLE: + break; + case AuxSwitchPos::LOW: + copter.air_mode = AirMode::AIRMODE_DISABLED; + break; + } + break; default: RC_Channel::do_aux_function(ch_option, ch_flag); diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index aa0802e0d7..db770dc626 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -107,6 +107,13 @@ enum GuidedMode { Guided_Angle, }; +// Airmode +enum class AirMode { + AIRMODE_NONE, + AIRMODE_DISABLED, + AIRMODE_ENABLED, +}; + // Safe RTL states enum SmartRTLState { SmartRTL_WaitForPathCleanup, diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index af8cfb5d67..6b5f4ebc7c 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -151,7 +151,7 @@ void Copter::update_throttle_mix() if (flightmode->has_manual_throttle()) { // manual throttle - if(channel_throttle->get_control_in() <= 0) { + if (channel_throttle->get_control_in() <= 0 || air_mode == AirMode::AIRMODE_DISABLED) { attitude_control->set_throttle_mix_min(); } else { attitude_control->set_throttle_mix_man(); diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 1f1a94a16a..5a496405df 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -180,7 +180,7 @@ void Copter::set_throttle_zero_flag(int16_t throttle_control) // and we are flying. Immediately set as non-zero if ((!ap.using_interlock && (throttle_control > 0) && !SRV_Channels::get_emergency_stop()) || (ap.using_interlock && motors->get_interlock()) || - ap.armed_with_switch) { + ap.armed_with_switch || air_mode == AirMode::AIRMODE_ENABLED) { last_nonzero_throttle_ms = tnow_ms; ap.throttle_zero = false; } else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) {