From c489841b3c5e0c98f9707b605a44f316c9d52515 Mon Sep 17 00:00:00 2001 From: Michelle Rossouw Date: Thu, 26 Oct 2023 22:59:26 +1100 Subject: [PATCH] Blimp: Simplify motors allocation --- Blimp/system.cpp | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/Blimp/system.cpp b/Blimp/system.cpp index 5b46cddb549e3a..388cec4b311164 100644 --- a/Blimp/system.cpp +++ b/Blimp/system.cpp @@ -254,15 +254,7 @@ const char* Blimp::get_frame_string() */ void Blimp::allocate_motors(void) { - switch ((Fins::motor_frame_class)g2.frame_class.get()) { - case Fins::MOTOR_FRAME_FOUR_MOTOR: - motors = new Fins(blimp.scheduler.get_loop_rate_hz(), Fins::MOTOR_FRAME_FOUR_MOTOR); - break; - case Fins::MOTOR_FRAME_FISHBLIMP: - default: - motors = new Fins(blimp.scheduler.get_loop_rate_hz(), Fins::MOTOR_FRAME_FISHBLIMP); - break; - } + motors = new Fins(blimp.scheduler.get_loop_rate_hz(), (Fins::motor_frame_class)g2.frame_class.get()); if (motors == nullptr) { AP_BoardConfig::allocation_error("FRAME_CLASS=%u", (unsigned)g2.frame_class.get()); }