diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index c04f34555b..854e90a9b6 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -115,6 +115,16 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { #endif }; + +void Rover::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, + uint8_t &task_count, + uint32_t &log_bit) +{ + tasks = &scheduler_tasks[0]; + task_count = ARRAY_SIZE(scheduler_tasks); + log_bit = MASK_LOG_PM; +} + constexpr int8_t Rover::_failsafe_priorities[7]; Rover::Rover(void) : @@ -141,19 +151,6 @@ void Rover::stats_update(void) } #endif -/* - setup is called when the sketch starts - */ -void Rover::setup() -{ - // load the default values of variables listed in var_info[] - AP_Param::setup_sketch_defaults(); - - init_ardupilot(); - - // initialise the main loop scheduler - scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), MASK_LOG_PM); -} /* loop() is called rapidly while the sketch is running diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index f2e826eaf1..85f1f56f14 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -127,7 +127,6 @@ public: Rover(void); // HAL::Callbacks implementation. - void setup(void) override; void loop(void) override; private: @@ -384,8 +383,13 @@ private: // Steering.cpp void set_servos(void); + // Rover.cpp + void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, + uint8_t &task_count, + uint32_t &log_bit) override; + // system.cpp - void init_ardupilot(); + void init_ardupilot() override; void startup_ground(void); void update_ahrs_flyforward(); bool set_mode(Mode &new_mode, ModeReason reason);