global: use static method to construct RangeFinder

This commit is contained in:
Lucas De Marchi 2017-08-25 10:23:01 -07:00 committed by Francisco Ferreira
parent 2e80b2e1d0
commit 9027a55696
9 changed files with 9 additions and 9 deletions

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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;

View File

@ -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

View File

@ -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};

View File

@ -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};

View File

@ -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};

View File

@ -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()
{