Browse Source

global: use static method to construct AP_AHRS_DCM

mission-4.1.18
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
bfd13dfe87
  1. 2
      APMrover2/Rover.h
  2. 2
      AntennaTracker/Tracker.h
  3. 2
      ArduPlane/Plane.h
  4. 2
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
  5. 2
      libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp
  6. 2
      libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp

2
APMrover2/Rover.h

@ -167,7 +167,7 @@ private: @@ -167,7 +167,7 @@ private:
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder);
AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3);
#else
AP_AHRS_DCM ahrs {ins, barometer, gps};
AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, barometer, gps);
#endif
// Arming/Disarming management class

2
AntennaTracker/Tracker.h

@ -120,7 +120,7 @@ private: @@ -120,7 +120,7 @@ private:
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rng);
AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3);
#else
AP_AHRS_DCM ahrs{ins, barometer, gps};
AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, barometer, gps);
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL

2
ArduPlane/Plane.h

@ -217,7 +217,7 @@ private: @@ -217,7 +217,7 @@ private:
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder);
AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3);
#else
AP_AHRS_DCM ahrs {ins, barometer, gps};
AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, barometer, gps);
#endif
AP_TECS TECS_controller {ahrs, aparm, landing, g2.soaring_controller};

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

@ -35,7 +35,7 @@ public: @@ -35,7 +35,7 @@ public:
static DummyVehicle vehicle;
// choose which AHRS system to use
// AP_AHRS_DCM ahrs(ins, baro, gps);
// AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, barometer, gps);
AP_AHRS_NavEKF &ahrs = vehicle.ahrs;
void setup(void)

2
libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp

@ -18,7 +18,7 @@ private: @@ -18,7 +18,7 @@ private:
AP_Baro baro = AP_Baro::create();
AP_GPS gps = AP_GPS::create();
Compass compass = Compass::create();
AP_AHRS_DCM ahrs{ins, baro, gps};
AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, baro, gps);
// global constants that control how many verify calls must be made for a command before it completes
uint8_t verify_nav_cmd_iterations_to_complete = 3;

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

@ -19,7 +19,7 @@ static AP_Baro baro = AP_Baro::create(); @@ -19,7 +19,7 @@ static AP_Baro baro = AP_Baro::create();
static AP_SerialManager serial_manager = AP_SerialManager::create();
// choose which AHRS system to use
AP_AHRS_DCM ahrs(ins, baro, gps);
static AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, baro, gps);
void setup(void)
{

Loading…
Cancel
Save