Skip to content

Commit

Permalink
global: use static method to construct AP_AHRS_DCM
Browse files Browse the repository at this point in the history
  • Loading branch information
lucasdemarchi authored and OXINARF committed Sep 26, 2017
1 parent cd1ff7b commit bfd13df
Show file tree
Hide file tree
Showing 6 changed files with 6 additions and 6 deletions.
2 changes: 1 addition & 1 deletion APMrover2/Rover.h
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ class Rover : public AP_HAL::HAL::Callbacks {
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
Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ class Tracker : public AP_HAL::HAL::Callbacks {
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
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ class Plane : public AP_HAL::HAL::Callbacks {
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};
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class DummyVehicle {
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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class MissionTest {
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;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down

0 comments on commit bfd13df

Please sign in to comment.