global: use static method to construct AP_SerialManager

This commit is contained in:
Lucas De Marchi 2017-08-28 15:03:27 -07:00 committed by Francisco Ferreira
parent 04866e9f76
commit 72fd2d6f05
12 changed files with 15 additions and 13 deletions

View File

@ -195,8 +195,9 @@ private:
SITL::SITL sitl; SITL::SITL sitl;
#endif #endif
AP_SerialManager serial_manager = AP_SerialManager::create();
// GCS handling // GCS handling
AP_SerialManager serial_manager;
GCS_Rover _gcs; // avoid using this; use gcs() GCS_Rover _gcs; // avoid using this; use gcs()
GCS_Rover &gcs() { return _gcs; } GCS_Rover &gcs() { return _gcs; }

View File

@ -139,7 +139,7 @@ private:
bool yaw_servo_out_filt_init = false; bool yaw_servo_out_filt_init = false;
bool pitch_servo_out_filt_init = false; bool pitch_servo_out_filt_init = false;
AP_SerialManager serial_manager; AP_SerialManager serial_manager = AP_SerialManager::create();
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; }

View File

@ -246,8 +246,9 @@ private:
uint32_t ekfYawReset_ms = 0; uint32_t ekfYawReset_ms = 0;
int8_t ekf_primary_core; int8_t ekf_primary_core;
AP_SerialManager serial_manager = AP_SerialManager::create();
// GCS selection // GCS selection
AP_SerialManager serial_manager;
GCS_Copter _gcs; // avoid using this; use gcs() GCS_Copter _gcs; // avoid using this; use gcs()
GCS_Copter &gcs() { return _gcs; } GCS_Copter &gcs() { return _gcs; }

View File

@ -254,9 +254,9 @@ private:
// external failsafe boards during baro and airspeed calibration // external failsafe boards during baro and airspeed calibration
bool in_calibration; bool in_calibration;
AP_SerialManager serial_manager = AP_SerialManager::create();
// GCS selection // GCS selection
AP_SerialManager serial_manager;
GCS_Plane _gcs; // avoid using this; use gcs() GCS_Plane _gcs; // avoid using this; use gcs()
GCS_Plane &gcs() { return _gcs; } GCS_Plane &gcs() { return _gcs; }

View File

@ -212,9 +212,9 @@ private:
// system time in milliseconds of last recorded yaw reset from ekf // system time in milliseconds of last recorded yaw reset from ekf
uint32_t ekfYawReset_ms = 0; uint32_t ekfYawReset_ms = 0;
// GCS selection AP_SerialManager serial_manager = AP_SerialManager::create();
AP_SerialManager serial_manager;
// GCS selection
GCS_Sub _gcs; // avoid using this; use gcs() GCS_Sub _gcs; // avoid using this; use gcs()
GCS_Sub &gcs() { return _gcs; } GCS_Sub &gcs() { return _gcs; }

View File

@ -62,7 +62,7 @@ public:
AP_Baro barometer = AP_Baro::create(); AP_Baro barometer = AP_Baro::create();
AP_GPS gps = AP_GPS::create(); AP_GPS gps = AP_GPS::create();
Compass compass = Compass::create(); Compass compass = Compass::create();
AP_SerialManager serial_manager; AP_SerialManager serial_manager = AP_SerialManager::create();
RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_PITCH_270); RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
NavEKF2 EKF2{&ahrs, barometer, rng}; NavEKF2 EKF2{&ahrs, barometer, rng};
NavEKF3 EKF3{&ahrs, barometer, rng}; NavEKF3 EKF3{&ahrs, barometer, rng};

View File

@ -19,7 +19,7 @@ static Compass compass = Compass::create();
static AP_GPS gps = AP_GPS::create(); static AP_GPS gps = AP_GPS::create();
static AP_Baro barometer = AP_Baro::create(); static AP_Baro barometer = AP_Baro::create();
AP_SerialManager serial_manager; static AP_SerialManager serial_manager = AP_SerialManager::create();
class DummyVehicle { class DummyVehicle {
public: public:

View File

@ -16,7 +16,7 @@ void set_object_value_and_report(const void *object_pointer,
const char *name, float value); const char *name, float value);
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_SerialManager serial_manager; static AP_SerialManager serial_manager = AP_SerialManager::create();
AP_Beacon beacon{serial_manager}; AP_Beacon beacon{serial_manager};
// try to set the object value but provide diagnostic if it failed // try to set the object value but provide diagnostic if it failed

View File

@ -43,7 +43,7 @@ AP_BoardLED board_led;
// This example uses GPS system. Create it. // This example uses GPS system. Create it.
static AP_GPS gps = AP_GPS::create(); static AP_GPS gps = AP_GPS::create();
// Serial manager is needed for UART comunications // Serial manager is needed for UART comunications
AP_SerialManager serial_manager; static AP_SerialManager serial_manager = AP_SerialManager::create();
void setup() void setup()

View File

@ -16,7 +16,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_InertialSensor ins = AP_InertialSensor::create(); static AP_InertialSensor ins = AP_InertialSensor::create();
static AP_GPS gps = AP_GPS::create(); static AP_GPS gps = AP_GPS::create();
static AP_Baro baro = AP_Baro::create(); static AP_Baro baro = AP_Baro::create();
AP_SerialManager serial_manager; static AP_SerialManager serial_manager = AP_SerialManager::create();
// choose which AHRS system to use // choose which AHRS system to use
AP_AHRS_DCM ahrs(ins, baro, gps); AP_AHRS_DCM ahrs(ins, baro, gps);

View File

@ -25,7 +25,7 @@ public:
AP_Baro barometer = AP_Baro::create(); AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::create(); Compass compass = Compass::create();
AP_InertialSensor ins = AP_InertialSensor::create(); AP_InertialSensor ins = AP_InertialSensor::create();
AP_SerialManager serial_manager; AP_SerialManager serial_manager = AP_SerialManager::create();
RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3,
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};

View File

@ -10,7 +10,7 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_SerialManager serial_manager; static AP_SerialManager serial_manager = AP_SerialManager::create();
static RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); static RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
void setup() void setup()