mirror of https://github.com/ArduPilot/ardupilot
global: use static method to construct AP_AHRS_DCM
This commit is contained in:
parent
cd1ff7b86f
commit
bfd13dfe87
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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};
|
||||
|
|
|
@ -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)
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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…
Reference in New Issue