AC_PrecLand: 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:
Andrew Tridgell 2017-12-13 12:06:10 +11:00
parent 25c409d4a2
commit 9ba8097502
1 changed files with 6 additions and 12 deletions

View File

@ -25,6 +25,12 @@ class AC_PrecLand
friend class AC_PrecLand_SITL;
public:
AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav);
/* Do not allow copies */
AC_PrecLand(const AC_PrecLand &other) = delete;
AC_PrecLand &operator=(const AC_PrecLand&) = delete;
// precision landing behaviours (held in PRECLAND_ENABLED parameter)
enum PrecLandBehaviour {
PRECLAND_BEHAVIOUR_DISABLED,
@ -41,16 +47,6 @@ public:
PRECLAND_TYPE_SITL,
};
static AC_PrecLand create(const AP_AHRS& ahrs, const AP_InertialNav& inav) {
return AC_PrecLand{ahrs, inav};
}
constexpr AC_PrecLand(AC_PrecLand &&other) = default;
/* Do not allow copies */
AC_PrecLand(const AC_PrecLand &other) = delete;
AC_PrecLand &operator=(const AC_PrecLand&) = delete;
// perform any required initialisation of landing controllers
void init();
@ -85,8 +81,6 @@ public:
static const struct AP_Param::GroupInfo var_info[];
private:
AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav);
enum estimator_type_t {
ESTIMATOR_TYPE_RAW_SENSOR = 0,
ESTIMATOR_TYPE_KALMAN_FILTER = 1