AP_Vehicle: compile without scheduler

This commit is contained in:
Peter Barker 2023-09-01 23:05:52 +10:00 committed by Peter Barker
parent a949b52b5a
commit 04ae9879f3
2 changed files with 4 additions and 0 deletions

View File

@ -307,6 +307,7 @@ void AP_Vehicle::setup()
} }
#endif #endif
#if AP_SCHEDULER_ENABLED
// initialise the main loop scheduler // initialise the main loop scheduler
const AP_Scheduler::Task *tasks; const AP_Scheduler::Task *tasks;
uint8_t task_count; uint8_t task_count;
@ -317,6 +318,7 @@ void AP_Vehicle::setup()
// time per loop - this gets updated in the main loop() based on // time per loop - this gets updated in the main loop() based on
// actual loop rate // actual loop rate
G_Dt = scheduler.get_loop_period_s(); G_Dt = scheduler.get_loop_period_s();
#endif
// this is here for Plane; its failsafe_check method requires the // this is here for Plane; its failsafe_check method requires the
// RC channels to be set as early as possible for maximum // RC channels to be set as early as possible for maximum

View File

@ -123,7 +123,9 @@ public:
void get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks); void get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks);
// implementations *MUST* fill in all passed-in fields or we get // implementations *MUST* fill in all passed-in fields or we get
// Valgrind errors // Valgrind errors
#if AP_SCHEDULER_ENABLED
virtual void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) = 0; virtual void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) = 0;
#endif
/* /*
set the "likely flying" flag. This is not guaranteed to be set the "likely flying" flag. This is not guaranteed to be