Browse Source

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

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
69b6d95cb2
  1. 4
      APMrover2/Rover.h
  2. 4
      AntennaTracker/Tracker.h
  3. 4
      ArduCopter/Copter.h
  4. 4
      ArduPlane/Plane.h
  5. 4
      ArduSub/Sub.h
  6. 5
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
  7. 3
      libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp
  8. 3
      libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp
  9. 3
      libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp
  10. 4
      libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp
  11. 2
      libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp
  12. 3
      libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp

4
APMrover2/Rover.h

@ -136,11 +136,11 @@ private: @@ -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

4
AntennaTracker/Tracker.h

@ -143,11 +143,11 @@ private: @@ -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;

4
ArduCopter/Copter.h

@ -317,11 +317,11 @@ private: @@ -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

4
ArduPlane/Plane.h

@ -172,11 +172,11 @@ private: @@ -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

4
ArduSub/Sub.h

@ -255,11 +255,11 @@ private: @@ -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

5
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

@ -13,6 +13,8 @@ void loop(); @@ -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); @@ -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();

3
libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp

@ -31,6 +31,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); @@ -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() @@ -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);

3
libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp

@ -12,6 +12,7 @@ static AP_Baro barometer = AP_Baro::create(); @@ -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() @@ -20,7 +21,7 @@ void setup()
{
hal.console->printf("Barometer library test\n");
AP_BoardConfig{}.init();
board_config.init();
hal.scheduler->delay(1000);

3
libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp

@ -9,6 +9,7 @@ @@ -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() @@ -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!");

4
libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp

@ -37,6 +37,8 @@ void loop(); @@ -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() @@ -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();

2
libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp

@ -14,7 +14,7 @@ static void display_offsets_and_scaling(); @@ -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);

3
libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp

@ -27,6 +27,7 @@ private: @@ -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[] = { @@ -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());

Loading…
Cancel
Save