mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Vehicle: add task info for fast loop
move fast loop tasks into scheduler table remove fast loop
This commit is contained in:
parent
01766eee01
commit
cc2acc35a6
@ -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
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user