From bf7474c940b399ff944b60ffc74eea5da8d8a093 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 12 Aug 2021 10:46:07 +1000 Subject: [PATCH] Blimp: DCM handles centrifugal correction application internally now --- Blimp/AP_Arming.cpp | 4 ---- Blimp/Parameters.cpp | 2 -- 2 files changed, 6 deletions(-) diff --git a/Blimp/AP_Arming.cpp b/Blimp/AP_Arming.cpp index 06889471ff..a308ae66ce 100644 --- a/Blimp/AP_Arming.cpp +++ b/Blimp/AP_Arming.cpp @@ -384,8 +384,6 @@ bool AP_Arming_Blimp::arm(const AP_Arming::Method method, const bool do_arming_c blimp.arming_altitude_m = blimp.inertial_nav.get_altitude() * 0.01; } - // enable gps velocity based centrifugal force compensation - ahrs.set_correct_centrifugal(true); hal.util->set_soft_armed(true); // finally actually arm the motors @@ -443,8 +441,6 @@ bool AP_Arming_Blimp::disarm(const AP_Arming::Method method, bool do_disarm_chec AP::logger().set_vehicle_armed(false); - // disable gps velocity based centrefugal force compensation - ahrs.set_correct_centrifugal(false); hal.util->set_soft_armed(false); blimp.ap.in_arming_delay = false; diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index 79d0de8b0e..523cec59ee 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -876,8 +876,6 @@ void Blimp::load_parameters(void) AP_HAL::panic("Bad var table"); } - // disable centrifugal force correction, it will be enabled as part of the arming process - ahrs.set_correct_centrifugal(false); hal.util->set_soft_armed(false); if (!g.format_version.load() ||