From 3fe1a69a32f1ff75240ddd136576c030bbdc7509 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 10 Jan 2017 06:44:54 +1100 Subject: [PATCH] Copter: always allocate a motors backend this allows autotest to run, and gives a less confusing error to users when no FRAME_CLASS error is selected --- ArduCopter/system.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 19b8d30ffb..04b9301598 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -542,6 +542,7 @@ void Copter::allocate_motors(void) case AP_Motors::MOTOR_FRAME_Y6: case AP_Motors::MOTOR_FRAME_OCTA: case AP_Motors::MOTOR_FRAME_OCTAQUAD: + default: motors = new AP_MotorsMatrix(MAIN_LOOP_RATE); break; case AP_Motors::MOTOR_FRAME_TRI: @@ -555,11 +556,10 @@ void Copter::allocate_motors(void) break; #else // FRAME_CONFIG == HELI_FRAME case AP_Motors::MOTOR_FRAME_HELI: + default: motors = new AP_MotorsHeli_Single(MAIN_LOOP_RATE); break; #endif - default: - break; } if (motors == nullptr) { AP_HAL::panic("Unable to allocate FRAME_CLASS=%u", (unsigned)g2.frame_class.get());