From 69b6d95cb2cbb545a1d5c731a26e8cbd331fd753 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Mon, 28 Aug 2017 17:45:57 -0700 Subject: [PATCH] global: use static method to construct AP_Board_Config{,_CAN} --- APMrover2/Rover.h | 4 ++-- AntennaTracker/Tracker.h | 4 ++-- ArduCopter/Copter.h | 4 ++-- ArduPlane/Plane.h | 4 ++-- ArduSub/Sub.h | 4 ++-- libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp | 5 +++-- libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp | 3 ++- libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp | 3 ++- .../AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp | 3 ++- libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp | 4 +++- .../AP_InertialSensor/examples/INS_generic/INS_generic.cpp | 2 +- .../AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp | 3 ++- 12 files changed, 25 insertions(+), 18 deletions(-) diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 03764b3e82..3cdb96024d 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -136,11 +136,11 @@ private: RCMapper rcmap = RCMapper::create(); // board specific config - AP_BoardConfig BoardConfig; + AP_BoardConfig BoardConfig = AP_BoardConfig::create(); #if HAL_WITH_UAVCAN // board specific config for CAN bus - AP_BoardConfig_CAN BoardConfig_CAN; + AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create(); #endif // primary control channels diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 6c70bdd9c8..22f56ebc73 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -143,11 +143,11 @@ private: GCS_Tracker _gcs; // avoid using this; use gcs() GCS_Tracker &gcs() { return _gcs; } - AP_BoardConfig BoardConfig; + AP_BoardConfig BoardConfig = AP_BoardConfig::create(); #if HAL_WITH_UAVCAN // board specific config for CAN bus - AP_BoardConfig_CAN BoardConfig_CAN; + AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create(); #endif struct Location current_loc; diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 63cf0edc54..80ac429a48 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -317,11 +317,11 @@ private: RCMapper rcmap = RCMapper::create(); // board specific config - AP_BoardConfig BoardConfig; + AP_BoardConfig BoardConfig = AP_BoardConfig::create(); #if HAL_WITH_UAVCAN // board specific config for CAN bus - AP_BoardConfig_CAN BoardConfig_CAN; + AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create(); #endif // receiver RSSI diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 89659005aa..49a5972180 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -172,11 +172,11 @@ private: RCMapper rcmap = RCMapper::create(); // board specific config - AP_BoardConfig BoardConfig; + AP_BoardConfig BoardConfig = AP_BoardConfig::create(); // board specific config for CAN bus #if HAL_WITH_UAVCAN - AP_BoardConfig_CAN BoardConfig_CAN; + AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create(); #endif // primary input channels diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 5855dcc0ea..4c67e6adb6 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -255,11 +255,11 @@ private: #endif // board specific config - AP_BoardConfig BoardConfig; + AP_BoardConfig BoardConfig = AP_BoardConfig::create(); #if HAL_WITH_UAVCAN // board specific config for CAN bus - AP_BoardConfig_CAN BoardConfig_CAN; + AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create(); #endif // Failsafe diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index bbf729aa2a..f70bc8be2a 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -13,6 +13,8 @@ void loop(); const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +static AP_BoardConfig board_config = AP_BoardConfig::create(); static AP_InertialSensor ins = AP_InertialSensor::create(); static Compass compass = Compass::create(); @@ -38,8 +40,7 @@ AP_AHRS_NavEKF ahrs(vehicle.ahrs); void setup(void) { - AP_BoardConfig{}.init(); - + board_config.init(); ins.init(100); ahrs.init(); serial_manager.init(); diff --git a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp index e7b035ee08..a6adfbed73 100644 --- a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp +++ b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp @@ -31,6 +31,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); float temperature; AP_Airspeed airspeed; +static AP_BoardConfig board_config = AP_BoardConfig::create(); namespace { // try to set the object value but provide diagnostic if it failed @@ -53,7 +54,7 @@ void setup() set_object_value(&airspeed, airspeed.var_info, "ENABLE", 1); set_object_value(&airspeed, airspeed.var_info, "USE", 1); - AP_BoardConfig{}.init(); + board_config.init(); airspeed.init(); airspeed.calibrate(false); diff --git a/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp b/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp index 64bea4d976..83373520af 100644 --- a/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp +++ b/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp @@ -12,6 +12,7 @@ static AP_Baro barometer = AP_Baro::create(); static uint32_t timer; static uint8_t counter; +static AP_BoardConfig board_config = AP_BoardConfig::create(); void setup(); void loop(); @@ -20,7 +21,7 @@ void setup() { hal.console->printf("Barometer library test\n"); - AP_BoardConfig{}.init(); + board_config.init(); hal.scheduler->delay(1000); diff --git a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp index cca63d595f..67341ea99d 100644 --- a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp +++ b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp @@ -9,6 +9,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); +static AP_BoardConfig board_config = AP_BoardConfig::create(); static Compass compass = Compass::create(); uint32_t timer; @@ -17,7 +18,7 @@ static void setup() { hal.console->printf("Compass library test\n"); - AP_BoardConfig{}.init(); // initialise the board drivers + board_config.init(); if (!compass.init()) { AP_HAL::panic("compass initialisation failed!"); diff --git a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp index 1e5d195fe3..e62789a439 100644 --- a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp +++ b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp @@ -37,6 +37,8 @@ void loop(); const AP_HAL::HAL& hal = AP_HAL::get_HAL(); +static AP_BoardConfig board_config = AP_BoardConfig::create(); + // create board led object AP_BoardLED board_led; @@ -50,7 +52,7 @@ void setup() { hal.console->printf("GPS AUTO library test\n"); - AP_BoardConfig{}.init(); + board_config.init(); // Initialise the leds board_led.init(); diff --git a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp index fe1d38e280..3dab715adf 100644 --- a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp +++ b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp @@ -14,7 +14,7 @@ static void display_offsets_and_scaling(); static void run_test(); // board specific config -AP_BoardConfig BoardConfig; +static AP_BoardConfig BoardConfig = AP_BoardConfig::create(); void setup(void); void loop(void); diff --git a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp index cfaeffdb96..d3b0376724 100644 --- a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp +++ b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp @@ -27,6 +27,7 @@ private: void five_second_call(void); }; +static AP_BoardConfig board_config = AP_BoardConfig::create(); static SchedTest schedtest; #define SCHED_TASK(func, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(SchedTest, &schedtest, func, _interval_ticks, _max_time_micros) @@ -46,7 +47,7 @@ const AP_Scheduler::Task SchedTest::scheduler_tasks[] = { void SchedTest::setup(void) { - AP_BoardConfig{}.init(); + board_config.init(); ins.init(scheduler.get_loop_rate_hz());