Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: do not enter airmode when armed with switch #18478

Merged
merged 15 commits into from
Sep 20, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions AntennaTracker/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ void Tracker::init_ardupilot()

// initialise rc channels including setting mode
rc().init();
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);

// initialise servos
init_servos();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -857,7 +857,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
copter.ap.in_arming_delay = true;

// assumed armed without a arming, switch. Overridden in switches.cpp
copter.ap.armed_with_switch = false;
copter.ap.armed_with_airmode_switch = false;

// return success
return true;
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -364,7 +364,7 @@ class Copter : public AP_Vehicle {
uint8_t initialised_params : 1; // 24 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
uint8_t unused3 : 1; // 25 // was compass_init_location; true when the compass's initial location has been set
uint8_t unused2 : 1; // 26 // aux switch rc_override is allowed
uint8_t armed_with_switch : 1; // 27 // we armed using a arming switch
uint8_t armed_with_airmode_switch : 1; // 27 // we armed using a arming switch
};
uint32_t value;
} ap_t;
Expand Down
18 changes: 8 additions & 10 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,7 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const AuxS
case AUX_FUNC::AUTO_RTL:
case AUX_FUNC::TURTLE:
case AUX_FUNC::SIMPLE_HEADING_RESET:
case AUX_FUNC::ARMDISARM_AIRMODE:
break;
case AUX_FUNC::ACRO_TRAINER:
case AUX_FUNC::ATTCON_ACCEL_LIM:
Expand Down Expand Up @@ -135,16 +136,6 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
}
}

void RC_Channel_Copter::do_aux_function_armdisarm(const AuxSwitchPos ch_flag)
{
RC_Channel::do_aux_function_armdisarm(ch_flag);
if (copter.arming.is_armed()) {
// remember that we are using an arming switch, for use by
// set_throttle_zero_flag
copter.ap.armed_with_switch = true;
}
}

// do_aux_function - implement the function invoked by auxiliary switches
bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
{
Expand Down Expand Up @@ -583,6 +574,13 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
}
break;

case AUX_FUNC::ARMDISARM_AIRMODE:
RC_Channel::do_aux_function_armdisarm(ch_flag);
if (copter.arming.is_armed()) {
copter.ap.armed_with_airmode_switch = true;
IamPete1 marked this conversation as resolved.
Show resolved Hide resolved
}
break;

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
}
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@ class RC_Channel_Copter : public RC_Channel

private:

void do_aux_function_armdisarm(const AuxSwitchPos ch_flag) override;
void do_aux_function_change_mode(const Mode::Number mode,
const AuxSwitchPos ch_flag);
void do_aux_function_change_air_mode(const AuxSwitchPos ch_flag);
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 || air_mode == AirMode::AIRMODE_ENABLED) {
ap.armed_with_airmode_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) {
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ void Copter::init_ardupilot()

// initialise rc channels including setting mode
rc().init();
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM_AIRMODE);

// sets up motors and output to escs
init_rc_out();
Expand Down
9 changes: 0 additions & 9 deletions ArduPlane/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,15 +220,6 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
return false;
}

#if HAL_QUADPLANE_ENABLED
if ((method == Method::AUXSWITCH) && (plane.quadplane.options & QuadPlane::OPTION_AIRMODE)) {
// if no airmode switch assigned, honour the QuadPlane option bit:
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr) {
plane.quadplane.air_mode = AirMode::ON;
}
}
#endif

change_arm_state();

// rising edge of delay_arming oneshot
Expand Down
15 changes: 14 additions & 1 deletion ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,11 +160,16 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
case AUX_FUNC::PARACHUTE_RELEASE:
case AUX_FUNC::MODE_SWITCH_RESET:
case AUX_FUNC::CRUISE:
#if HAL_QUADPLANE_ENABLED
case AUX_FUNC::ARMDISARM_AIRMODE:
#endif
break;

case AUX_FUNC::Q_ASSIST:
case AUX_FUNC::SOARING:
#if HAL_QUADPLANE_ENABLED
case AUX_FUNC::Q_ASSIST:
case AUX_FUNC::AIRMODE:
#endif
#if AP_AIRSPEED_AUTOCAL_ENABLE
case AUX_FUNC::ARSPD_CALIBRATE:
#endif
Expand Down Expand Up @@ -333,6 +338,14 @@ case AUX_FUNC::ARSPD_CALIBRATE:
do_aux_function_change_mode(Mode::Number::CRUISE, ch_flag);
break;

#if HAL_QUADPLANE_ENABLED
case AUX_FUNC::ARMDISARM_AIRMODE:
RC_Channel::do_aux_function_armdisarm(ch_flag);
if (plane.arming.is_armed()) {
plane.quadplane.air_mode = AirMode::ON;
}
break;
#endif

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -309,7 +309,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: OPTIONS
// @DisplayName: quadplane options
// @Description: Level Transition:Keep wings within LEVEL_ROLL_LIMIT and only use forward motor(s) for climb during transition, Allow FW Takeoff: If bit is not set then NAV_TAKEOFF command on quadplanes will instead perform a NAV_VTOL takeoff, Allow FW Land:If bit is not set then NAV_LAND command on quadplanes will instead perform a NAV_VTOL_LAND, Vtol Takeoff Frame: command NAV_VTOL_TAKEOFF altitude is as set by the command's reference frame rather than a delta above current location, Use FW Approach:Use a fixed wing approach for VTOL landings, USE QRTL:instead of QLAND for rc failsafe when in VTOL modes, Use Governor:Use ICE Idle Governor in MANUAL for forward motor, Force Qassist: on always,Mtrs_Only_Qassist: in tailsitters only, uses VTOL motors and not flying surfaces for QASSIST, Airmode_On_Arm:Airmode enabled when arming by aux switch, Disarmed Yaw Tilt:Enable motor tilt for yaw when disarmed, Delay Spoolup:Delay VTOL spoolup for 2 seconds after arming, ThrLandControl: enable throttle stick control of landing rate, DisableApproach: Disable use of approach and airbrake stages in VTOL landing, EnableLandResponsition: enable pilot controlled repositioning in AUTO land. Descent will pause while repositioning.
// @Bitmask: 0:Level Transition,1:Allow FW Takeoff,2:Allow FW Land,3:Vtol Takeoff Frame,4:Use FW Approach,5:Use QRTL,6:Use Governor,7:Force Qassist,8:Mtrs_Only_Qassist,9:Airmode_On_Arm,10:Disarmed Yaw Tilt,11:Delay Spoolup,12:disable Qassist based on synthetic airspeed,13:Disable Ground Effect Compensation,14:Ignore forward flight angle limits in Qmodes,15:ThrLandControl,16:DisableApproach,17:EnableLandResponsition,18:Only allow arming in Qmodes or auto
// @Bitmask: 0:Level Transition,1:Allow FW Takeoff,2:Allow FW Land,3:Vtol Takeoff Frame,4:Use FW Approach,5:Use QRTL,6:Use Governor,7:Force Qassist,8:Mtrs_Only_Qassist,10:Disarmed Yaw Tilt,11:Delay Spoolup,12:disable Qassist based on synthetic airspeed,13:Disable Ground Effect Compensation,14:Ignore forward flight angle limits in Qmodes,15:ThrLandControl,16:DisableApproach,17:EnableLandResponsition,18:Only allow arming in Qmodes or auto
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),

AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -546,7 +546,7 @@ class QuadPlane
OPTION_IDLE_GOV_MANUAL=(1<<6),
OPTION_Q_ASSIST_FORCE_ENABLE=(1<<7),
OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY=(1<<8),
OPTION_AIRMODE=(1<<9),
OPTION_AIRMODE_UNUSED=(1<<9),
OPTION_DISARMED_TILT=(1<<10),
OPTION_DELAY_ARMING=(1<<11),
OPTION_DISABLE_SYNTHETIC_AIRSPEED_ASSIST=(1<<12),
Expand Down
5 changes: 5 additions & 0 deletions ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,11 @@ void Plane::init_ardupilot()

// initialise rc channels including setting mode
rc().init();
#if HAL_QUADPLANE_ENABLED
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, (quadplane.enabled() && (quadplane.options & QuadPlane::OPTION_AIRMODE_UNUSED) && (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr)) ? RC_Channel::AUX_FUNC::ARMDISARM_AIRMODE : RC_Channel::AUX_FUNC::ARMDISARM);
#else
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
#endif

relay.init();

Expand Down
1 change: 1 addition & 0 deletions ArduSub/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ void Sub::init_ardupilot()

// initialise rc channels including setting mode
rc().init();
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);

init_rc_in(); // sets up rc channels from radio
init_rc_out(); // sets up motors and output to escs
Expand Down
1 change: 1 addition & 0 deletions Blimp/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ void Blimp::init_ardupilot()

// initialise rc channels including setting mode
rc().init();
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);

// sets up motors and output to escs
init_rc_out();
Expand Down
1 change: 1 addition & 0 deletions Rover/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,7 @@ void Rover::init_ardupilot()

// initialise rc channels
rc().init();
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);

rover.g2.sailboat.init();

Expand Down
4 changes: 2 additions & 2 deletions Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -7570,7 +7570,7 @@ def test_arm_feature(self):

self.start_subtest("Test arm and disarm with switch")
arming_switch = 7
self.set_parameter("RC%d_OPTION" % arming_switch, 41)
self.set_parameter("RC%d_OPTION" % arming_switch, 153)
self.set_rc(arming_switch, 1000)
# delay so a transition is seen by the RC switch code:
self.delay_sim_time(0.5)
Expand Down Expand Up @@ -9582,7 +9582,7 @@ def test_button(self):
return

self.wait_ready_to_arm()
self.set_parameter("BTN_FUNC%u" % btn, 41) # ARM/DISARM
self.set_parameter("BTN_FUNC%u" % btn, 153) # ARM/DISARM
self.set_parameter("SIM_PIN_MASK", mask)
self.wait_armed()
self.set_parameter("SIM_PIN_MASK", 0)
Expand Down
8 changes: 2 additions & 6 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -117,11 +117,7 @@ def test_airmode(self):
self.progress("Verify Motor1 is at min_pwm when disarmed")
self.wait_servo_channel_value(5, min_pwm, comparator=operator.eq)

"""set Q_OPTIONS bit AIRMODE"""
airmode_option_bit = (1 << 9)
self.set_parameter("Q_OPTIONS", airmode_option_bit)

armdisarm_option = 41
armdisarm_option = 154
arm_ch = 8
self.set_parameter("RC%d_OPTION" % arm_ch, armdisarm_option)
self.progress("Configured RC%d as ARMDISARM switch" % arm_ch)
Expand All @@ -147,7 +143,7 @@ def test_airmode(self):
if (spin_arm_pwm >= spin_min_pwm):
raise PreconditionFailedException("SPIN_MIN pwm not greater than SPIN_ARM pwm")

self.start_subtest("Test auxswitch arming with Q_OPTIONS=AirMode")
self.start_subtest("Test auxswitch arming with AirMode Switch")
for mode in ('QSTABILIZE', 'QACRO'):
"""verify that arming with switch results in higher PWM output"""
self.progress("Testing %s mode" % mode)
Expand Down
Loading