global: use static method to construct AP_AHRS_DCM

This commit is contained in:
Lucas De Marchi 2017-08-30 01:15:47 -07:00 committed by Francisco Ferreira
parent cd1ff7b86f
commit bfd13dfe87
6 changed files with 6 additions and 6 deletions

View File

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

View File

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

View File

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

View File

@ -35,7 +35,7 @@ public:
static DummyVehicle vehicle; static DummyVehicle vehicle;
// choose which AHRS system to use // 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; AP_AHRS_NavEKF &ahrs = vehicle.ahrs;
void setup(void) void setup(void)

View File

@ -18,7 +18,7 @@ private:
AP_Baro baro = AP_Baro::create(); AP_Baro baro = AP_Baro::create();
AP_GPS gps = AP_GPS::create(); AP_GPS gps = AP_GPS::create();
Compass compass = Compass::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 // 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; uint8_t verify_nav_cmd_iterations_to_complete = 3;

View File

@ -19,7 +19,7 @@ static AP_Baro baro = AP_Baro::create();
static AP_SerialManager serial_manager = AP_SerialManager::create(); 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); static AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(ins, baro, gps);
void setup(void) void setup(void)
{ {