Plane: fixed motor test with DShot VTOL motors

need to arm when running the motor test
This commit is contained in:
Andrew Tridgell 2021-07-04 18:20:29 +10:00
parent b5bb401b97
commit 002bc51fd5
1 changed files with 1 additions and 1 deletions

View File

@ -264,7 +264,7 @@ bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_chec
void AP_Arming_Plane::update_soft_armed()
{
hal.util->set_soft_armed(is_armed() &&
hal.util->set_soft_armed((plane.quadplane.motor_test.running || is_armed()) &&
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
AP::logger().set_vehicle_armed(hal.util->get_soft_armed());