Browse Source

Plane: move setup method up to AP_Vehicle base class

c415-sdk
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
a45abc7762
  1. 18
      ArduPlane/ArduPlane.cpp
  2. 6
      ArduPlane/Plane.h

18
ArduPlane/ArduPlane.cpp

@ -112,19 +112,17 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { @@ -112,19 +112,17 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(update_dynamic_notch, 50, 200),
};
constexpr int8_t Plane::_failsafe_priorities[7];
void Plane::setup()
void Plane::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[]
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 Plane::_failsafe_priorities[7];
void Plane::loop()
{
scheduler.loop();

6
ArduPlane/Plane.h

@ -161,7 +161,6 @@ public: @@ -161,7 +161,6 @@ public:
Plane(void);
// HAL::Callbacks implementation.
void setup() override;
void loop() override;
private:
@ -896,7 +895,10 @@ private: @@ -896,7 +895,10 @@ private:
void read_airspeed(void);
void rpm_update(void);
void efi_update(void);
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_ground(void);
bool set_mode(Mode& new_mode, const ModeReason reason);
bool set_mode(const uint8_t mode, const ModeReason reason) override;

Loading…
Cancel
Save