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

Start moving bulk amounts of init_ardupilot to base class #13299

Merged
merged 17 commits into from
Jan 28, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
17 commits
Select commit Hold shift + click to select a range
2be1838
StorageManager: use pragmas to set storage layout rather than call
peterbarker Jan 16, 2020
614097d
Copter: StorageManager layout is now done with a pragma
peterbarker Jan 16, 2020
b2799fb
Plane: move rssi initialisation into init_ardupilot
peterbarker Jan 16, 2020
dd48c0a
Rover: move setup method up to AP_Vehicle base class
peterbarker Jan 16, 2020
a6a174e
Tracker: move setup method up to AP_Vehicle base class
peterbarker Jan 16, 2020
815bcfd
Copter: move setup method up to AP_Vehicle base class
peterbarker Jan 16, 2020
25de7ff
Plane: move setup method up to AP_Vehicle base class
peterbarker Jan 16, 2020
5c3b02f
Sub: move setup method up to AP_Vehicle base class
peterbarker Jan 16, 2020
8d6f2e4
AP_Vehicle: move setup method up to AP_Vehicle base class
peterbarker Jan 16, 2020
7cc5cba
AP_Vehicle: move some common init_ardupilot code up to AP_Vehicle
peterbarker Jan 16, 2020
fe0aa80
AntennaTracker: move some common init_ardupilot code up to AP_Vehicle
peterbarker Jan 16, 2020
6c0fb0f
APMrover2: move some common init_ardupilot code up to AP_Vehicle
peterbarker Jan 16, 2020
b6daf74
ArduCopter: move some common init_ardupilot code up to AP_Vehicle
peterbarker Jan 16, 2020
07f2e5b
ArduPlane: move some common init_ardupilot code up to AP_Vehicle
peterbarker Jan 16, 2020
da161f9
ArduSub: move some common init_ardupilot code up to AP_Vehicle
peterbarker Jan 16, 2020
9ea9e8b
AP_Periph: fix up firmware version includes
peterbarker Jan 16, 2020
e6fb070
Tools: adjust Replay for new AP_Vehicle requirements
peterbarker Jan 16, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 10 additions & 13 deletions APMrover2/Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,16 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
#endif
};


void Rover::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit)
{
tasks = &scheduler_tasks[0];
task_count = ARRAY_SIZE(scheduler_tasks);
log_bit = MASK_LOG_PM;
}

constexpr int8_t Rover::_failsafe_priorities[7];

Rover::Rover(void) :
Expand All @@ -141,19 +151,6 @@ void Rover::stats_update(void)
}
#endif

/*
setup is called when the sketch starts
*/
void Rover::setup()
{
// 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);
}

/*
loop() is called rapidly while the sketch is running
Expand Down
10 changes: 7 additions & 3 deletions APMrover2/Rover.h
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,6 @@ class Rover : public AP_Vehicle {
Rover(void);

// HAL::Callbacks implementation.
void setup(void) override;
void loop(void) override;

private:
Expand Down Expand Up @@ -362,7 +361,7 @@ class Rover : public AP_Vehicle {
Mode *mode_from_mode_num(enum Mode::Number num);

// Parameters.cpp
void load_parameters(void);
void load_parameters(void) override;

// radio.cpp
void set_control_channels(void);
Expand All @@ -384,8 +383,13 @@ class Rover : public AP_Vehicle {
// Steering.cpp
void set_servos(void);

// Rover.cpp
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;

// system.cpp
void init_ardupilot();
void init_ardupilot() override;
void startup_ground(void);
void update_ahrs_flyforward();
bool set_mode(Mode &new_mode, ModeReason reason);
Expand Down
14 changes: 0 additions & 14 deletions APMrover2/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@ The init_ardupilot function processes everything we need for an in - air restart
*****************************************************************************/

#include "Rover.h"
#include <AP_Common/AP_FWVersion.h>

static void failsafe_check_static()
{
Expand All @@ -15,19 +14,6 @@ static void failsafe_check_static()

void Rover::init_ardupilot()
{
// initialise console serial port
serial_manager.init_console();

hal.console->printf("\n\nInit %s"
"\n\nFree RAM: %u\n",
AP::fwversion().fw_string,
(unsigned)hal.util->available_memory());

//
// Check the EEPROM format version before loading any parameters from EEPROM.
//

load_parameters();
#if STATS_ENABLED == ENABLED
// initialise stats module
g2.stats.init();
Expand Down
17 changes: 6 additions & 11 deletions AntennaTracker/Tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,18 +55,13 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
SCHED_TASK(accel_cal_update, 10, 100)
};

/**
setup the sketch - called once on startup
*/
void Tracker::setup()
void Tracker::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_tracker();

// initialise the main loop scheduler
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), (uint32_t)-1);
tasks = &scheduler_tasks[0];
task_count = ARRAY_SIZE(scheduler_tasks);
log_bit = (uint32_t)-1;
}

/**
Expand Down
13 changes: 6 additions & 7 deletions AntennaTracker/Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@
#include <AP_Mission/AP_Mission.h>
#include <AP_Stats/AP_Stats.h> // statistics library
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
#include <AP_Common/AP_FWVersion.h>

// Configuration
#include "config.h"
Expand Down Expand Up @@ -74,10 +73,7 @@ class Tracker : public AP_Vehicle {

Tracker(void);

static const AP_FWVersion fwver;

// HAL::Callbacks implementation.
void setup() override;
void loop() override;

private:
Expand Down Expand Up @@ -174,7 +170,10 @@ class Tracker : public AP_Vehicle {
// true if the compass's initial location has been set
bool compass_init_location;

// AntennaTracker.cpp
// Tracker.cpp
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
void one_second_loop();
void ten_hz_logging_loop();
void stats_update();
Expand All @@ -190,7 +189,7 @@ class Tracker : public AP_Vehicle {
void log_init(void);

// Parameters.cpp
void load_parameters(void);
void load_parameters(void) override;

// radio.cpp
void read_radio();
Expand All @@ -215,7 +214,7 @@ class Tracker : public AP_Vehicle {
void update_yaw_cr_servo(float yaw);

// system.cpp
void init_tracker();
void init_ardupilot() override;
bool get_home_eeprom(struct Location &loc);
bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;
bool set_home(const Location &temp) WARN_IF_UNUSED;
Expand Down
12 changes: 1 addition & 11 deletions AntennaTracker/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,18 +3,8 @@
// mission storage
static const StorageAccess wp_storage(StorageManager::StorageMission);

void Tracker::init_tracker()
void Tracker::init_ardupilot()
{
// initialise console serial port
serial_manager.init_console();

hal.console->printf("\n\nInit %s\n\nFree RAM: %u\n",
AP::fwversion().fw_string,
(unsigned)hal.util->available_memory());

// Check the EEPROM format version before loading any parameters from EEPROM
load_parameters();

// initialise stats module
stats.init();

Expand Down
21 changes: 8 additions & 13 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,22 +209,17 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#endif
};

constexpr int8_t Copter::_failsafe_priorities[7];

void Copter::setup()
void Copter::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();

// setup storage layout for copter
StorageManager::set_layout_copter();

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 Copter::_failsafe_priorities[7];

void Copter::loop()
{
scheduler.loop();
Expand Down
12 changes: 6 additions & 6 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,6 @@
#include <AP_SmartRTL/AP_SmartRTL.h>
#include <AP_TempCalibration/AP_TempCalibration.h>
#include <AC_AutoTune/AC_AutoTune.h>
#include <AP_Common/AP_FWVersion.h>
#include <AP_Parachute/AP_Parachute.h>
#include <AC_Sprayer/AC_Sprayer.h>

Expand Down Expand Up @@ -236,11 +235,9 @@ class Copter : public AP_Vehicle {
Copter(void);

// HAL::Callbacks implementation.
void setup() override;
void loop() override;

private:
static const AP_FWVersion fwver;

// key aircraft parameters passed to multiple libraries
AP_Vehicle::MultiCopter aparm;
Expand Down Expand Up @@ -640,7 +637,10 @@ class Copter : public AP_Vehicle {
void set_failsafe_gcs(bool b);
void update_using_interlock();

// ArduCopter.cpp
// Copter.cpp
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
void fast_loop();
void rc_loop();
void throttle_loop();
Expand Down Expand Up @@ -816,7 +816,7 @@ class Copter : public AP_Vehicle {
uint32_t home_distance();

// Parameters.cpp
void load_parameters(void);
void load_parameters(void) override;
void convert_pid_parameters(void);
void convert_lgr_parameters(void);
void convert_tradheli_parameters(void);
Expand Down Expand Up @@ -859,7 +859,7 @@ class Copter : public AP_Vehicle {
void auto_trim();

// system.cpp
void init_ardupilot();
void init_ardupilot() override;
void startup_INS_ground();
void update_dynamic_notch();
bool position_ok() const;
Expand Down
11 changes: 0 additions & 11 deletions ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,17 +15,6 @@ static void failsafe_check_static()

void Copter::init_ardupilot()
{
// initialise serial port
serial_manager.init_console();

hal.console->printf("\n\nInit %s"
"\n\nFree RAM: %u\n",
AP::fwversion().fw_string,
(unsigned)hal.util->available_memory());

// load parameters from EEPROM
load_parameters();

// time per loop - this gets updated in the main loop() based on
// actual loop rate
G_Dt = 1.0 / scheduler.get_loop_rate_hz();
Expand Down
20 changes: 8 additions & 12 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,21 +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();

rssi.init();

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();
Expand Down
8 changes: 5 additions & 3 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,6 @@ class Plane : public AP_Vehicle {
Plane(void);

// HAL::Callbacks implementation.
void setup() override;
void loop() override;

private:
Expand Down Expand Up @@ -790,7 +789,7 @@ class Plane : public AP_Vehicle {
void Log_Write_AOA_SSA();
void Log_Write_AETR();

void load_parameters(void);
void load_parameters(void) override;
void convert_mixers(void);
void adjust_altitude_target();
void setup_glide_slope(void);
Expand Down Expand Up @@ -896,7 +895,10 @@ class Plane : public AP_Vehicle {
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;
Expand Down
15 changes: 2 additions & 13 deletions ArduPlane/system.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#include "Plane.h"
#include <AP_Common/AP_FWVersion.h>

/*****************************************************************************
* The init_ardupilot function processes everything we need for an in - air restart
Expand All @@ -15,18 +14,6 @@ static void failsafe_check_static()

void Plane::init_ardupilot()
{
// initialise serial port
serial_manager.init_console();

hal.console->printf("\n\nInit %s"
"\n\nFree RAM: %u\n",
AP::fwversion().fw_string,
(unsigned)hal.util->available_memory());

//
// Check the EEPROM format version before loading any parameters from EEPROM
//
load_parameters();

#if STATS_ENABLED == ENABLED
// initialise stats module
Expand Down Expand Up @@ -85,6 +72,8 @@ void Plane::init_ardupilot()
// initialise battery monitoring
battery.init();

rssi.init();

rpm_sensor.init();

// setup telem slots with serial ports
Expand Down
Loading