diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 6a98e70d5a..eaa1490415 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -155,7 +155,7 @@ private: AP_Baro barometer = AP_Baro::create(); Compass compass = Compass::create(); AP_InertialSensor ins = AP_InertialSensor::create(); - RangeFinder rangefinder { serial_manager, ROTATION_NONE }; + RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_NONE); AP_Button button; // flight modes convenience array diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index ff2bd5289a..a19322668b 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -112,7 +112,7 @@ private: AP_InertialSensor ins = AP_InertialSensor::create(); - RangeFinder rng {serial_manager, ROTATION_NONE}; + RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_NONE); // Inertial Navigation EKF #if AP_AHRS_NAVEKF_AVAILABLE diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 4f142b47d9..c3ea3f6ee9 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -201,7 +201,7 @@ private: Compass compass = Compass::create(); AP_InertialSensor ins = AP_InertialSensor::create(); - RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270}; + RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270); struct { bool enabled:1; bool alt_healthy:1; // true if we can trust the altitude from the rangefinder diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index b763d312c7..37a6c6f12a 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -205,7 +205,7 @@ private: AP_InertialSensor ins = AP_InertialSensor::create(); - RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270}; + RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270); AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state; diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 954840c755..b8d53358e3 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -170,7 +170,7 @@ private: Compass compass = Compass::create(); AP_InertialSensor ins = AP_InertialSensor::create(); - RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270}; + RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270); struct { bool enabled:1; bool alt_healthy:1; // true if we can trust the altitude from the rangefinder diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index 994fea67cf..ceaf5aa1b3 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -63,7 +63,7 @@ public: AP_GPS gps = AP_GPS::create(); Compass compass = Compass::create(); AP_SerialManager serial_manager; - RangeFinder rng {serial_manager, ROTATION_PITCH_270}; + RangeFinder rng = RangeFinder::create(serial_manager, ROTATION_PITCH_270); NavEKF2 EKF2{&ahrs, barometer, rng}; NavEKF3 EKF3{&ahrs, barometer, rng}; AP_AHRS_NavEKF ahrs {ins, barometer, gps, rng, EKF2, EKF3}; diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index 806012bfa8..de3ac3d1b8 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -23,7 +23,7 @@ AP_SerialManager serial_manager; class DummyVehicle { public: - RangeFinder sonar {serial_manager, ROTATION_PITCH_270}; + RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); AP_AHRS_NavEKF ahrs{ins, barometer, gps, sonar, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; NavEKF2 EKF2{&ahrs, barometer, sonar}; diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp index 9063df6928..94298f84b6 100644 --- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp +++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp @@ -26,7 +26,7 @@ public: Compass compass = Compass::create(); AP_InertialSensor ins = AP_InertialSensor::create(); AP_SerialManager serial_manager; - RangeFinder sonar {serial_manager, ROTATION_PITCH_270}; + RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); AP_AHRS_NavEKF ahrs{ins, barometer, gps, sonar, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; NavEKF2 EKF2{&ahrs, barometer, sonar}; diff --git a/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp b/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp index 5174264e6f..710f44377a 100644 --- a/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp +++ b/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp @@ -11,7 +11,7 @@ void loop(); const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static AP_SerialManager serial_manager; -static RangeFinder sonar {serial_manager, ROTATION_PITCH_270}; +static RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270); void setup() {