From ad99b04de70c05457713ad05fbea772bfff2e41e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 13 Dec 2017 12:06:12 +1100 Subject: [PATCH] AP_LandingGear: 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 --- libraries/AP_LandingGear/AP_LandingGear.h | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/libraries/AP_LandingGear/AP_LandingGear.h b/libraries/AP_LandingGear/AP_LandingGear.h index 7f0af1cb4c..f1216eb100 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.h +++ b/libraries/AP_LandingGear/AP_LandingGear.h @@ -12,9 +12,10 @@ /// @brief Class managing the control of landing gear class AP_LandingGear { public: - static AP_LandingGear create() { return AP_LandingGear{}; } - - constexpr AP_LandingGear(AP_LandingGear &&other) = default; + AP_LandingGear() { + // setup parameter defaults + AP_Param::setup_object_defaults(this, var_info); + } /* Do not allow copies */ AP_LandingGear(const AP_LandingGear &other) = delete; @@ -46,11 +47,6 @@ public: static const struct AP_Param::GroupInfo var_info[]; private: - AP_LandingGear() { - // setup parameter defaults - AP_Param::setup_object_defaults(this, var_info); - } - // Parameters AP_Int16 _servo_retract_pwm; // PWM value to move servo to when gear is retracted AP_Int16 _servo_deploy_pwm; // PWM value to move servo to when gear is deployed