mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_Vehicle: separate gyrofft gyro sampling from fft initiation
move FFT gyro sampling into fast loop for all vehicles rename FFT update method
This commit is contained in:
parent
13e40a3002
commit
d873ec4533
@ -113,6 +113,16 @@ void AP_Vehicle::loop()
|
|||||||
G_Dt = scheduler.get_loop_period_s();
|
G_Dt = scheduler.get_loop_period_s();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
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
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
common scheduler table for fast CPUs - all common vehicle tasks
|
common scheduler table for fast CPUs - all common vehicle tasks
|
||||||
should be listed here, along with how often they should be called (in hz)
|
should be listed here, along with how often they should be called (in hz)
|
||||||
@ -123,7 +133,7 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
|
|||||||
SCHED_TASK_CLASS(AP_RunCam, &vehicle.runcam, update, 50, 50),
|
SCHED_TASK_CLASS(AP_RunCam, &vehicle.runcam, update, 50, 50),
|
||||||
#endif
|
#endif
|
||||||
#if HAL_GYROFFT_ENABLED
|
#if HAL_GYROFFT_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, sample_gyros, LOOP_RATE, 50),
|
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, update, 400, 50),
|
||||||
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, update_parameters, 1, 50),
|
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, update_parameters, 1, 50),
|
||||||
#endif
|
#endif
|
||||||
SCHED_TASK(send_watchdog_reset_statustext, 0.1, 20),
|
SCHED_TASK(send_watchdog_reset_statustext, 0.1, 20),
|
||||||
|
@ -190,7 +190,7 @@ protected:
|
|||||||
|
|
||||||
// main loop scheduler
|
// main loop scheduler
|
||||||
AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&AP_Vehicle::fast_loop, void)};
|
AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&AP_Vehicle::fast_loop, void)};
|
||||||
virtual void fast_loop() { }
|
virtual void fast_loop();
|
||||||
|
|
||||||
// IMU variables
|
// IMU variables
|
||||||
// Integration time; time last loop took to run
|
// Integration time; time last loop took to run
|
||||||
|
Loading…
Reference in New Issue
Block a user