mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
global: use static method to construct AP_Scheduler
This commit is contained in:
parent
d3e12eb899
commit
de680dac5b
@ -130,7 +130,7 @@ private:
|
||||
ParametersG2 g2;
|
||||
|
||||
// main loop scheduler
|
||||
AP_Scheduler scheduler;
|
||||
AP_Scheduler scheduler = AP_Scheduler::create();
|
||||
|
||||
// mapping between input channels
|
||||
RCMapper rcmap;
|
||||
|
@ -93,8 +93,8 @@ private:
|
||||
Parameters g;
|
||||
|
||||
// main loop scheduler
|
||||
AP_Scheduler scheduler;
|
||||
|
||||
AP_Scheduler scheduler = AP_Scheduler::create();
|
||||
|
||||
// notification object for LEDs, buzzers etc
|
||||
AP_Notify notify;
|
||||
|
||||
|
@ -175,7 +175,7 @@ private:
|
||||
ParametersG2 g2;
|
||||
|
||||
// main loop scheduler
|
||||
AP_Scheduler scheduler;
|
||||
AP_Scheduler scheduler = AP_Scheduler::create();
|
||||
|
||||
// AP_Notify instance
|
||||
AP_Notify notify;
|
||||
|
@ -166,8 +166,8 @@ private:
|
||||
ParametersG2 g2;
|
||||
|
||||
// main loop scheduler
|
||||
AP_Scheduler scheduler;
|
||||
|
||||
AP_Scheduler scheduler = AP_Scheduler::create();
|
||||
|
||||
// mapping between input channels
|
||||
RCMapper rcmap;
|
||||
|
||||
|
@ -145,7 +145,7 @@ private:
|
||||
ParametersG2 g2;
|
||||
|
||||
// main loop scheduler
|
||||
AP_Scheduler scheduler;
|
||||
AP_Scheduler scheduler = AP_Scheduler::create();
|
||||
|
||||
// AP_Notify instance
|
||||
AP_Notify notify;
|
||||
|
@ -17,7 +17,7 @@ public:
|
||||
private:
|
||||
|
||||
AP_InertialSensor ins = AP_InertialSensor::create();
|
||||
AP_Scheduler scheduler;
|
||||
AP_Scheduler scheduler = AP_Scheduler::create();
|
||||
|
||||
uint32_t ins_counter;
|
||||
static const AP_Scheduler::Task scheduler_tasks[];
|
||||
|
Loading…
Reference in New Issue
Block a user