mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Vehicle: move initialisation of serial and gcs to AP_Vehicle
This commit is contained in:
parent
2b7af4d70b
commit
2ede027635
@ -58,6 +58,25 @@ void AP_Vehicle::setup()
|
||||
// actual loop rate
|
||||
G_Dt = scheduler.get_loop_period_s();
|
||||
|
||||
// this is here for Plane; its failsafe_check method requires the
|
||||
// RC channels to be set as early as possible for maximum
|
||||
// survivability.
|
||||
set_control_channels();
|
||||
|
||||
// initialise serial manager as early as sensible to get
|
||||
// diagnostic output during boot process. We have to initialise
|
||||
// the GCS singleton first as it sets the global mavlink system ID
|
||||
// which may get used very early on.
|
||||
gcs().init();
|
||||
|
||||
// initialise serial ports
|
||||
serial_manager.init();
|
||||
gcs().setup_console();
|
||||
|
||||
// Register scheduler_delay_cb, which will run anytime you have
|
||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||
hal.scheduler->register_delay_callback(scheduler_delay_callback, 5);
|
||||
|
||||
// init_ardupilot is where the vehicle does most of its initialisation.
|
||||
init_ardupilot();
|
||||
// gyro FFT needs to be initialized really late
|
||||
@ -134,13 +153,6 @@ void AP_Vehicle::scheduler_delay_callback()
|
||||
logger.EnableWrites(true);
|
||||
}
|
||||
|
||||
void AP_Vehicle::register_scheduler_delay_callback()
|
||||
{
|
||||
// Register scheduler_delay_cb, which will run anytime you have
|
||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||
hal.scheduler->register_delay_callback(scheduler_delay_callback, 5);
|
||||
}
|
||||
|
||||
AP_Vehicle *AP_Vehicle::_singleton = nullptr;
|
||||
|
||||
AP_Vehicle *AP_Vehicle::get_singleton()
|
||||
|
@ -165,6 +165,7 @@ protected:
|
||||
|
||||
virtual void init_ardupilot() = 0;
|
||||
virtual void load_parameters() = 0;
|
||||
virtual void set_control_channels() {}
|
||||
|
||||
// board specific config
|
||||
AP_BoardConfig BoardConfig;
|
||||
@ -223,8 +224,6 @@ protected:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
static const struct AP_Scheduler::Task scheduler_tasks[];
|
||||
|
||||
void register_scheduler_delay_callback();
|
||||
|
||||
private:
|
||||
|
||||
static AP_Vehicle *_singleton;
|
||||
|
Loading…
Reference in New Issue
Block a user