mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Vehicle: make init_vehicle() public
and protect against double call. This is needed for the call from AP_BoardConfig
This commit is contained in:
parent
5c342c3dab
commit
9d8821f3d7
@ -40,7 +40,12 @@ void AP_Vehicle::get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, ui
|
||||
}
|
||||
|
||||
// initialize the vehicle
|
||||
void AP_Vehicle::init_vehicle() {
|
||||
void AP_Vehicle::init_vehicle()
|
||||
{
|
||||
if (init_done) {
|
||||
return;
|
||||
}
|
||||
init_done = true;
|
||||
#if HAL_RUNCAM_ENABLED
|
||||
runcam.init();
|
||||
#endif
|
||||
|
@ -112,6 +112,9 @@ 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();
|
||||
|
||||
protected:
|
||||
|
||||
// board specific config
|
||||
@ -153,15 +156,13 @@ protected:
|
||||
AP_AHRS_DCM ahrs;
|
||||
#endif
|
||||
|
||||
// initialize the vehicle
|
||||
void init_vehicle();
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
static const struct AP_Scheduler::Task scheduler_tasks[];
|
||||
|
||||
private:
|
||||
|
||||
static AP_Vehicle *_singleton;
|
||||
bool init_done;
|
||||
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user