fix(commander): allow RC-switch arming in Auto Takeoff

The FW Takeoff Mode docs describe arming after entering the mode, which
is also the natural one-step launch flow with the v1.17 two-state
climb-out + loiter implementation. Commander.cpp:636 denied this for
all non-manual modes, predating the Takeoff feature work. Narrowly
exempt AUTO_TAKEOFF and AUTO_VTOL_TAKEOFF from the rc_switch /
rc_button / stick_gesture denial, leaving AUTO_MISSION and the rest
unchanged.

Closes #27012

Signed-off-by: Ramon Roche <mrpollo@gmail.com>
This commit is contained in:
Ramon Roche
2026-04-27 16:31:12 -06:00
parent 3ac9b267ca
commit 515aa2ea25
+5 -3
View File
@@ -633,9 +633,11 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_
}
}
} else if (calling_reason == arm_disarm_reason_t::stick_gesture
|| calling_reason == arm_disarm_reason_t::rc_switch
|| calling_reason == arm_disarm_reason_t::rc_button) {
} else if ((calling_reason == arm_disarm_reason_t::stick_gesture
|| calling_reason == arm_disarm_reason_t::rc_switch
|| calling_reason == arm_disarm_reason_t::rc_button)
&& _vehicle_status.nav_state != vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF
&& _vehicle_status.nav_state != vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF) {
mavlink_log_critical(&_mavlink_log_pub, "Arming denied: switch to manual mode first\t");
events::send(events::ID("commander_arm_denied_not_manual"), {events::Log::Critical, events::LogInternal::Info},