mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Vehicle: compile without scheduler
This commit is contained in:
parent
a949b52b5a
commit
04ae9879f3
@ -307,6 +307,7 @@ void AP_Vehicle::setup()
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_SCHEDULER_ENABLED
|
||||
// initialise the main loop scheduler
|
||||
const AP_Scheduler::Task *tasks;
|
||||
uint8_t task_count;
|
||||
@ -317,6 +318,7 @@ void AP_Vehicle::setup()
|
||||
// time per loop - this gets updated in the main loop() based on
|
||||
// actual loop rate
|
||||
G_Dt = scheduler.get_loop_period_s();
|
||||
#endif
|
||||
|
||||
// this is here for Plane; its failsafe_check method requires the
|
||||
// RC channels to be set as early as possible for maximum
|
||||
|
@ -123,7 +123,9 @@ public:
|
||||
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
|
||||
// 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;
|
||||
#endif
|
||||
|
||||
/*
|
||||
set the "likely flying" flag. This is not guaranteed to be
|
||||
|
Loading…
Reference in New Issue
Block a user