Copter: move setup method up to AP_Vehicle base class

This commit is contained in:
Peter Barker 2020-01-16 21:31:50 +11:00 committed by Andrew Tridgell
parent dfc274e547
commit debedd9d34
2 changed files with 13 additions and 13 deletions

View File

@ -209,19 +209,17 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#endif
};
constexpr int8_t Copter::_failsafe_priorities[7];
void Copter::setup()
void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit)
{
// Load the default values of variables listed in var_info[]s
AP_Param::setup_sketch_defaults();
init_ardupilot();
// initialise the main loop scheduler
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), MASK_LOG_PM);
tasks = &scheduler_tasks[0];
task_count = ARRAY_SIZE(scheduler_tasks);
log_bit = MASK_LOG_PM;
}
constexpr int8_t Copter::_failsafe_priorities[7];
void Copter::loop()
{
scheduler.loop();

View File

@ -236,7 +236,6 @@ public:
Copter(void);
// HAL::Callbacks implementation.
void setup() override;
void loop() override;
private:
@ -640,7 +639,10 @@ private:
void set_failsafe_gcs(bool b);
void update_using_interlock();
// ArduCopter.cpp
// Copter.cpp
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
void fast_loop();
void rc_loop();
void throttle_loop();
@ -859,7 +861,7 @@ private:
void auto_trim();
// system.cpp
void init_ardupilot();
void init_ardupilot() override;
void startup_INS_ground();
void update_dynamic_notch();
bool position_ok() const;