Browse Source

global: use static method to construct AP_SerialManager

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
72fd2d6f05
  1. 3
      APMrover2/Rover.h
  2. 2
      AntennaTracker/Tracker.h
  3. 3
      ArduCopter/Copter.h
  4. 2
      ArduPlane/Plane.h
  5. 4
      ArduSub/Sub.h
  6. 2
      Tools/Replay/Replay.h
  7. 2
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
  8. 2
      libraries/AP_Beacon/examples/AP_Marvelmind_test/AP_Marvelmind_test.cpp
  9. 2
      libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp
  10. 2
      libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp
  11. 2
      libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp
  12. 2
      libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp

3
APMrover2/Rover.h

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

2
AntennaTracker/Tracker.h

@ -139,7 +139,7 @@ private: @@ -139,7 +139,7 @@ private:
bool yaw_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() { return _gcs; }

3
ArduCopter/Copter.h

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

2
ArduPlane/Plane.h

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

4
ArduSub/Sub.h

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

2
Tools/Replay/Replay.h

@ -62,7 +62,7 @@ public: @@ -62,7 +62,7 @@ public:
AP_Baro barometer = AP_Baro::create();
AP_GPS gps = AP_GPS::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);
NavEKF2 EKF2{&ahrs, barometer, rng};
NavEKF3 EKF3{&ahrs, barometer, rng};

2
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

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

2
libraries/AP_Beacon/examples/AP_Marvelmind_test/AP_Marvelmind_test.cpp

@ -16,7 +16,7 @@ void set_object_value_and_report(const void *object_pointer, @@ -16,7 +16,7 @@ void set_object_value_and_report(const void *object_pointer,
const char *name, float value);
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};
// try to set the object value but provide diagnostic if it failed

2
libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp

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

2
libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp

@ -16,7 +16,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); @@ -16,7 +16,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_InertialSensor ins = AP_InertialSensor::create();
static AP_GPS gps = AP_GPS::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
AP_AHRS_DCM ahrs(ins, baro, gps);

2
libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp

@ -25,7 +25,7 @@ public: @@ -25,7 +25,7 @@ public:
AP_Baro barometer = AP_Baro::create();
Compass compass = Compass::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);
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3,
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};

2
libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp

@ -10,7 +10,7 @@ void loop(); @@ -10,7 +10,7 @@ void loop();
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);
void setup()

Loading…
Cancel
Save