Plane: fixed handling of arming with safety on

if safety is on and you force arm them turn safety off then Q modes
cannot run the motors as the AP_Motors armed state will still be off.

This ensures that the motors are armed immediately we arm. This
matches what copter does when arming with safety on
This commit is contained in:
Andrew Tridgell 2024-02-03 14:23:05 +11:00 committed by Randy Mackay
parent e2bccebfb8
commit 813c9e8f7f
1 changed files with 1 additions and 1 deletions

View File

@ -294,7 +294,7 @@ void AP_Arming_Plane::change_arm_state(void)
{
update_soft_armed();
#if HAL_QUADPLANE_ENABLED
plane.quadplane.set_armed(is_armed_and_safety_off());
plane.quadplane.set_armed(hal.util->get_soft_armed());
#endif
}