From cc2acc35a6b98b079f1b4e8f5e2bb389abbd2cab Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 1 Apr 2022 20:56:39 +0100 Subject: [PATCH] AP_Vehicle: add task info for fast loop move fast loop tasks into scheduler table remove fast loop --- libraries/AP_Vehicle/AP_Vehicle.cpp | 13 +++---------- libraries/AP_Vehicle/AP_Vehicle.h | 3 +-- 2 files changed, 4 insertions(+), 12 deletions(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 04d9b8fd40..862cc720ea 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -246,16 +246,6 @@ void AP_Vehicle::loop() } } -/* - fast loop callback for all vehicles. This will get called at the end of any vehicle-specific fast loop. - */ -void AP_Vehicle::fast_loop() -{ -#if HAL_GYROFFT_ENABLED - gyro_fft.sample_gyros(); -#endif -} - /* scheduler table - all regular tasks apart from the fast_loop() should be listed here. @@ -283,6 +273,9 @@ SCHED_TASK_CLASS arguments: */ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { +#if HAL_GYROFFT_ENABLED + FAST_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, sample_gyros), +#endif #if AP_AIRSPEED_ENABLED SCHED_TASK_CLASS(AP_Airspeed, &vehicle.airspeed, update, 10, 100, 41), // NOTE: the priority number here should be right before Plane's calc_airspeed_errors #endif diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index eabd7b801b..3102f79535 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -307,8 +307,7 @@ protected: #endif // main loop scheduler - AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&AP_Vehicle::fast_loop, void)}; - virtual void fast_loop(); + AP_Scheduler scheduler; // IMU variables // Integration time; time last loop took to run