AP_Vehicle: fold init_vehicle back into AP_Vehicle init method

This commit is contained in:
Peter Barker 2020-02-18 12:59:18 +11:00 committed by Andrew Tridgell
parent a7c493d037
commit 2b7af4d70b
2 changed files with 6 additions and 21 deletions

View File

@ -64,6 +64,12 @@ void AP_Vehicle::setup()
#if HAL_GYROFFT_ENABLED
gyro_fft.init(AP::scheduler().get_loop_period_us());
#endif
#if HAL_RUNCAM_ENABLED
runcam.init();
#endif
#if HAL_HOTT_TELEM_ENABLED
hott_telem.init();
#endif
}
void AP_Vehicle::loop()
@ -93,22 +99,6 @@ void AP_Vehicle::get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, ui
num_tasks = ARRAY_SIZE(scheduler_tasks);
}
// initialize the vehicle
void AP_Vehicle::init_vehicle()
{
if (init_done) {
return;
}
init_done = true;
#if HAL_RUNCAM_ENABLED
runcam.init();
#endif
#if HAL_HOTT_TELEM_ENABLED
hott_telem.init();
#endif
}
/*
* a delay() callback that processes MAVLink packets. We set this as the
* callback in long running library initialisation routines to allow

View File

@ -127,10 +127,6 @@ public:
};
void get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks);
// initialize the vehicle. Called from AP_BoardConfig
void init_vehicle();
virtual void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) = 0;
/*
@ -232,7 +228,6 @@ protected:
private:
static AP_Vehicle *_singleton;
bool init_done;
static void scheduler_delay_callback();