Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Move init_vehicle call into AP_Vehicle #13596

Merged
merged 2 commits into from Feb 25, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
6 changes: 0 additions & 6 deletions libraries/AP_BoardConfig/AP_BoardConfig.cpp
Expand Up @@ -322,12 +322,6 @@ void AP_BoardConfig::init()
printf("SDCard failed to start\n");
}
#endif

// run any the vehicle initialization routines
AP_Vehicle *vehicle = AP::vehicle();
if (vehicle) {
vehicle->init_vehicle();
}
}

// set default value for BRD_SAFETY_MASK
Expand Down
22 changes: 6 additions & 16 deletions libraries/AP_Vehicle/AP_Vehicle.cpp
Expand Up @@ -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()
Expand Down Expand Up @@ -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
Expand Down
5 changes: 0 additions & 5 deletions libraries/AP_Vehicle/AP_Vehicle.h
Expand Up @@ -127,10 +127,6 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
};

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;

/*
Expand Down Expand Up @@ -232,7 +228,6 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
private:

static AP_Vehicle *_singleton;
bool init_done;

static void scheduler_delay_callback();

Expand Down