From 18670d681e8343e06bc6405a680fac340c544c00 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Jan 2020 12:34:25 +1100 Subject: [PATCH] Copter: let AP_Vehicle handle loop() --- ArduCopter/Copter.cpp | 7 ------- ArduCopter/Copter.h | 14 +------------- ArduCopter/system.cpp | 3 --- 3 files changed, 1 insertion(+), 23 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 0819e23e0a..130bc1df87 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -220,13 +220,6 @@ void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, constexpr int8_t Copter::_failsafe_priorities[7]; -void Copter::loop() -{ - scheduler.loop(); - G_Dt = scheduler.get_last_loop_time_s(); -} - - // Main loop - 400hz void Copter::fast_loop() { diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 393082ebb5..11c62d30e3 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -56,7 +56,6 @@ #include #include // circle navigation library #include // ArduPilot Mega Declination Helper Library -#include // main loop scheduler #include // RC input mapping library #include // Battery monitor library #include // Landing Gear library @@ -234,9 +233,6 @@ public: Copter(void); - // HAL::Callbacks implementation. - void loop() override; - private: // key aircraft parameters passed to multiple libraries @@ -246,9 +242,6 @@ private: Parameters g; ParametersG2 g2; - // main loop scheduler - AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Copter::fast_loop, void)}; - // used to detect MAVLink acks from GCS to stop compassmot uint8_t command_ack_counter; @@ -458,11 +451,6 @@ private: // Current location of the vehicle (altitude is relative to home) Location current_loc; - // IMU variables - // Integration time (in seconds) for the gyros (DCM algorithm) - // Updated with the fast loop - float G_Dt; - // Inertial Navigation AP_InertialNav_NavEKF inertial_nav; @@ -641,7 +629,7 @@ private: void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) override; - void fast_loop(); + void fast_loop() override; void rc_loop(); void throttle_loop(); void update_batt_compass(void); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index f09d5f4297..fdbf16f86e 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -15,9 +15,6 @@ static void failsafe_check_static() void Copter::init_ardupilot() { - // time per loop - this gets updated in the main loop() based on - // actual loop rate - G_Dt = 1.0 / scheduler.get_loop_rate_hz(); #if STATS_ENABLED == ENABLED // initialise stats module