mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow: removed create() method for objects
See discussion here: https://github.com/ArduPilot/ardupilot/issues/7331 we were getting some uninitialised variables. While it only showed up in AP_SbusOut, it means we can't be sure it won't happen on other objects, so safest to remove the approach Thanks to assistance from Lucas, Peter and Francisco
This commit is contained in:
parent
cd51c71857
commit
0d4dca0394
|
@ -30,9 +30,7 @@ class OpticalFlow
|
|||
friend class OpticalFlow_backend;
|
||||
|
||||
public:
|
||||
static OpticalFlow create(AP_AHRS_NavEKF& ahrs) { return OpticalFlow{ahrs}; }
|
||||
|
||||
constexpr OpticalFlow(OpticalFlow &&other) = default;
|
||||
OpticalFlow(AP_AHRS_NavEKF& ahrs);
|
||||
|
||||
/* Do not allow copies */
|
||||
OpticalFlow(const OpticalFlow &other) = delete;
|
||||
|
@ -81,8 +79,6 @@ public:
|
|||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
OpticalFlow(AP_AHRS_NavEKF& ahrs);
|
||||
|
||||
AP_AHRS_NavEKF &_ahrs;
|
||||
OpticalFlow_backend *backend;
|
||||
|
||||
|
|
|
@ -21,20 +21,19 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
|
||||
class DummyVehicle {
|
||||
public:
|
||||
AP_GPS gps = AP_GPS::create();
|
||||
AP_Baro barometer = AP_Baro::create();
|
||||
Compass compass = Compass::create();
|
||||
AP_InertialSensor ins = AP_InertialSensor::create();
|
||||
AP_SerialManager serial_manager = AP_SerialManager::create();
|
||||
RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
|
||||
AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3,
|
||||
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF);
|
||||
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, sonar);
|
||||
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, sonar);
|
||||
AP_GPS gps;
|
||||
AP_Baro barometer;
|
||||
Compass compass;
|
||||
AP_InertialSensor ins;
|
||||
AP_SerialManager serial_manager;
|
||||
RangeFinder sonar{serial_manager, ROTATION_PITCH_270};
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, gps, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
||||
NavEKF2 EKF2{&ahrs, barometer, sonar};
|
||||
NavEKF3 EKF3{&ahrs, barometer, sonar};
|
||||
};
|
||||
|
||||
static DummyVehicle vehicle;
|
||||
static OpticalFlow optflow = OpticalFlow::create(vehicle.ahrs);
|
||||
static OpticalFlow optflow{vehicle.ahrs};
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue