AP_Vehicle: initialise scheduler early

So the loop rate gets clamped before we memoise it and the loop period
in AP_Scheduler
This commit is contained in:
Peter Barker 2020-01-29 10:06:37 +11:00 committed by Peter Barker
parent 5580196b1c
commit de2cf89b60

View File

@ -42,20 +42,19 @@ void AP_Vehicle::setup()
load_parameters();
// time per loop - this gets updated in the main loop() based on
// actual loop rate. Note carefully that scheduler().init() has
// NOT been called yet!
G_Dt = scheduler.get_loop_period_s();
// init_ardupilot is where the vehicle does most of its initialisation.
init_ardupilot();
// initialise the main loop scheduler
const AP_Scheduler::Task *tasks;
uint8_t task_count;
uint32_t log_bit;
get_scheduler_tasks(tasks, task_count, log_bit);
AP::scheduler().init(tasks, task_count, log_bit);
// time per loop - this gets updated in the main loop() based on
// actual loop rate
G_Dt = scheduler.get_loop_period_s();
// init_ardupilot is where the vehicle does most of its initialisation.
init_ardupilot();
}
void AP_Vehicle::loop()