mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed motor test with DShot VTOL motors
need to arm when running the motor test
This commit is contained in:
parent
1f324d7cbf
commit
ff93999a94
|
@ -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());
|
||||
|
||||
|
|
Loading…
Reference in New Issue