mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Vehicle: call scripting update from 1Hz loop
This commit is contained in:
parent
2a3a5b2804
commit
433f98fee1
@ -22,6 +22,7 @@
|
||||
#include <AP_IOMCU/AP_IOMCU.h>
|
||||
extern AP_IOMCU iomcu;
|
||||
#endif
|
||||
#include <AP_Scripting/AP_Scripting.h>
|
||||
|
||||
#define SCHED_TASK(func, rate_hz, max_time_micros, prio) SCHED_TASK_CLASS(AP_Vehicle, &vehicle, func, rate_hz, max_time_micros, prio)
|
||||
|
||||
@ -562,9 +563,7 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
|
||||
#if HAL_EFI_ENABLED
|
||||
SCHED_TASK_CLASS(AP_EFI, &vehicle.efi, update, 50, 200, 250),
|
||||
#endif
|
||||
#if HAL_INS_ACCELCAL_ENABLED
|
||||
SCHED_TASK(one_Hz_update, 1, 100, 252),
|
||||
#endif
|
||||
#if HAL_WITH_ESC_TELEM && HAL_GYROFFT_ENABLED
|
||||
SCHED_TASK(check_motor_noise, 5, 50, 252),
|
||||
#endif
|
||||
@ -944,6 +943,14 @@ void AP_Vehicle::one_Hz_update(void)
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
AP_Scripting *scripting = AP_Scripting::get_singleton();
|
||||
if (scripting != nullptr) {
|
||||
scripting->update();
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void AP_Vehicle::check_motor_noise()
|
||||
|
Loading…
Reference in New Issue
Block a user