global: use static method to construct AP_Board_Config{,_CAN}

This commit is contained in:
Lucas De Marchi 2017-08-28 17:45:57 -07:00 committed by Francisco Ferreira
parent ef3edc531c
commit 69b6d95cb2
12 changed files with 25 additions and 18 deletions

View File

@ -136,11 +136,11 @@ private:
RCMapper rcmap = RCMapper::create(); RCMapper rcmap = RCMapper::create();
// board specific config // board specific config
AP_BoardConfig BoardConfig; AP_BoardConfig BoardConfig = AP_BoardConfig::create();
#if HAL_WITH_UAVCAN #if HAL_WITH_UAVCAN
// board specific config for CAN bus // board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN; AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create();
#endif #endif
// primary control channels // primary control channels

View File

@ -143,11 +143,11 @@ private:
GCS_Tracker _gcs; // avoid using this; use gcs() GCS_Tracker _gcs; // avoid using this; use gcs()
GCS_Tracker &gcs() { return _gcs; } GCS_Tracker &gcs() { return _gcs; }
AP_BoardConfig BoardConfig; AP_BoardConfig BoardConfig = AP_BoardConfig::create();
#if HAL_WITH_UAVCAN #if HAL_WITH_UAVCAN
// board specific config for CAN bus // board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN; AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create();
#endif #endif
struct Location current_loc; struct Location current_loc;

View File

@ -317,11 +317,11 @@ private:
RCMapper rcmap = RCMapper::create(); RCMapper rcmap = RCMapper::create();
// board specific config // board specific config
AP_BoardConfig BoardConfig; AP_BoardConfig BoardConfig = AP_BoardConfig::create();
#if HAL_WITH_UAVCAN #if HAL_WITH_UAVCAN
// board specific config for CAN bus // board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN; AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create();
#endif #endif
// receiver RSSI // receiver RSSI

View File

@ -172,11 +172,11 @@ private:
RCMapper rcmap = RCMapper::create(); RCMapper rcmap = RCMapper::create();
// board specific config // board specific config
AP_BoardConfig BoardConfig; AP_BoardConfig BoardConfig = AP_BoardConfig::create();
// board specific config for CAN bus // board specific config for CAN bus
#if HAL_WITH_UAVCAN #if HAL_WITH_UAVCAN
AP_BoardConfig_CAN BoardConfig_CAN; AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create();
#endif #endif
// primary input channels // primary input channels

View File

@ -255,11 +255,11 @@ private:
#endif #endif
// board specific config // board specific config
AP_BoardConfig BoardConfig; AP_BoardConfig BoardConfig = AP_BoardConfig::create();
#if HAL_WITH_UAVCAN #if HAL_WITH_UAVCAN
// board specific config for CAN bus // board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN; AP_BoardConfig_CAN BoardConfig_CAN = AP_BoardConfig_CAN::create();
#endif #endif
// Failsafe // Failsafe

View File

@ -13,6 +13,8 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); 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 AP_InertialSensor ins = AP_InertialSensor::create();
static Compass compass = Compass::create(); static Compass compass = Compass::create();
@ -38,8 +40,7 @@ AP_AHRS_NavEKF ahrs(vehicle.ahrs);
void setup(void) void setup(void)
{ {
AP_BoardConfig{}.init(); board_config.init();
ins.init(100); ins.init(100);
ahrs.init(); ahrs.init();
serial_manager.init(); serial_manager.init();

View File

@ -31,6 +31,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
float temperature; float temperature;
AP_Airspeed airspeed; AP_Airspeed airspeed;
static AP_BoardConfig board_config = AP_BoardConfig::create();
namespace { namespace {
// try to set the object value but provide diagnostic if it failed // 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, "ENABLE", 1);
set_object_value(&airspeed, airspeed.var_info, "USE", 1); set_object_value(&airspeed, airspeed.var_info, "USE", 1);
AP_BoardConfig{}.init(); board_config.init();
airspeed.init(); airspeed.init();
airspeed.calibrate(false); airspeed.calibrate(false);

View File

@ -12,6 +12,7 @@ static AP_Baro barometer = AP_Baro::create();
static uint32_t timer; static uint32_t timer;
static uint8_t counter; static uint8_t counter;
static AP_BoardConfig board_config = AP_BoardConfig::create();
void setup(); void setup();
void loop(); void loop();
@ -20,7 +21,7 @@ void setup()
{ {
hal.console->printf("Barometer library test\n"); hal.console->printf("Barometer library test\n");
AP_BoardConfig{}.init(); board_config.init();
hal.scheduler->delay(1000); hal.scheduler->delay(1000);

View File

@ -9,6 +9,7 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_BoardConfig board_config = AP_BoardConfig::create();
static Compass compass = Compass::create(); static Compass compass = Compass::create();
uint32_t timer; uint32_t timer;
@ -17,7 +18,7 @@ static void setup()
{ {
hal.console->printf("Compass library test\n"); hal.console->printf("Compass library test\n");
AP_BoardConfig{}.init(); // initialise the board drivers board_config.init();
if (!compass.init()) { if (!compass.init()) {
AP_HAL::panic("compass initialisation failed!"); AP_HAL::panic("compass initialisation failed!");

View File

@ -37,6 +37,8 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_BoardConfig board_config = AP_BoardConfig::create();
// create board led object // create board led object
AP_BoardLED board_led; AP_BoardLED board_led;
@ -50,7 +52,7 @@ void setup()
{ {
hal.console->printf("GPS AUTO library test\n"); hal.console->printf("GPS AUTO library test\n");
AP_BoardConfig{}.init(); board_config.init();
// Initialise the leds // Initialise the leds
board_led.init(); board_led.init();

View File

@ -14,7 +14,7 @@ static void display_offsets_and_scaling();
static void run_test(); static void run_test();
// board specific config // board specific config
AP_BoardConfig BoardConfig; static AP_BoardConfig BoardConfig = AP_BoardConfig::create();
void setup(void); void setup(void);
void loop(void); void loop(void);

View File

@ -27,6 +27,7 @@ private:
void five_second_call(void); void five_second_call(void);
}; };
static AP_BoardConfig board_config = AP_BoardConfig::create();
static SchedTest schedtest; static SchedTest schedtest;
#define SCHED_TASK(func, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(SchedTest, &schedtest, func, _interval_ticks, _max_time_micros) #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) void SchedTest::setup(void)
{ {
AP_BoardConfig{}.init(); board_config.init();
ins.init(scheduler.get_loop_rate_hz()); ins.init(scheduler.get_loop_rate_hz());