Skip to content

Commit

Permalink
AP_Vehicle: call scripting update from 1Hz loop
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 committed Dec 3, 2023
1 parent defc39b commit f7967b4
Showing 1 changed file with 9 additions and 2 deletions.
11 changes: 9 additions & 2 deletions libraries/AP_Vehicle/AP_Vehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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()
Expand Down

0 comments on commit f7967b4

Please sign in to comment.