mirror of https://github.com/ArduPilot/ardupilot
Sub: move setup method up to AP_Vehicle base class
This commit is contained in:
parent
a45abc7762
commit
87b84ec196
|
@ -80,19 +80,17 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||
#endif
|
||||
};
|
||||
|
||||
constexpr int8_t Sub::_failsafe_priorities[5];
|
||||
|
||||
void Sub::setup()
|
||||
void Sub::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 Sub::_failsafe_priorities[5];
|
||||
|
||||
void Sub::loop()
|
||||
{
|
||||
scheduler.loop();
|
||||
|
|
|
@ -132,7 +132,6 @@ public:
|
|||
Sub(void);
|
||||
|
||||
// HAL::Callbacks implementation.
|
||||
void setup() override;
|
||||
void loop() override;
|
||||
|
||||
private:
|
||||
|
@ -573,7 +572,10 @@ private:
|
|||
#endif
|
||||
void terrain_update();
|
||||
void terrain_logging();
|
||||
void init_ardupilot();
|
||||
void init_ardupilot() override;
|
||||
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
||||
uint8_t &task_count,
|
||||
uint32_t &log_bit) override;
|
||||
void startup_INS_ground();
|
||||
bool position_ok();
|
||||
bool ekf_position_ok();
|
||||
|
|
Loading…
Reference in New Issue