diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index b6eb50a22c..f9e7e7cfe6 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -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; diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 88b8b88e4b..8fe4fa2795 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -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; diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 45de9ab3ee..c1abdf98f4 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -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; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 820f4bb588..7d55d06749 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -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; diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 6f85c55ca7..9290c52b8c 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -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; diff --git a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp index 8e0d139ea2..cfaeffdb96 100644 --- a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp +++ b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp @@ -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[];