Copter: add air mode aux function

This commit is contained in:
Andy Piper 2020-05-24 12:26:00 +01:00 committed by Peter Barker
parent 1280eff6ef
commit 8d2f2443a2
5 changed files with 25 additions and 2 deletions

View File

@ -374,6 +374,8 @@ private:
ap_t ap; 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"); static_assert(sizeof(uint32_t) == sizeof(ap), "ap_t must be uint32_t");
// This is the state of the flight control system // This is the state of the flight control system

View File

@ -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::SUPERSIMPLE_MODE:
case AUX_FUNC::SURFACE_TRACKING: case AUX_FUNC::SURFACE_TRACKING:
case AUX_FUNC::WINCH_ENABLE: case AUX_FUNC::WINCH_ENABLE:
case AUX_FUNC::AIRMODE:
do_aux_function(ch_option, ch_flag); do_aux_function(ch_option, ch_flag);
break; break;
default: default:
@ -594,6 +595,19 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
#endif #endif
break; 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: default:
RC_Channel::do_aux_function(ch_option, ch_flag); RC_Channel::do_aux_function(ch_option, ch_flag);
break; break;

View File

@ -107,6 +107,13 @@ enum GuidedMode {
Guided_Angle, Guided_Angle,
}; };
// Airmode
enum class AirMode {
AIRMODE_NONE,
AIRMODE_DISABLED,
AIRMODE_ENABLED,
};
// Safe RTL states // Safe RTL states
enum SmartRTLState { enum SmartRTLState {
SmartRTL_WaitForPathCleanup, SmartRTL_WaitForPathCleanup,

View File

@ -151,7 +151,7 @@ void Copter::update_throttle_mix()
if (flightmode->has_manual_throttle()) { if (flightmode->has_manual_throttle()) {
// 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(); attitude_control->set_throttle_mix_min();
} else { } else {
attitude_control->set_throttle_mix_man(); attitude_control->set_throttle_mix_man();

View File

@ -180,7 +180,7 @@ void Copter::set_throttle_zero_flag(int16_t throttle_control)
// and we are flying. Immediately set as non-zero // and we are flying. Immediately set as non-zero
if ((!ap.using_interlock && (throttle_control > 0) && !SRV_Channels::get_emergency_stop()) || if ((!ap.using_interlock && (throttle_control > 0) && !SRV_Channels::get_emergency_stop()) ||
(ap.using_interlock && motors->get_interlock()) || (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; last_nonzero_throttle_ms = tnow_ms;
ap.throttle_zero = false; ap.throttle_zero = false;
} else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) { } else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) {