AP_Relay: 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:14 +11:00
parent e9b847b5ee
commit 16cd31b63a

View File

@ -17,9 +17,7 @@
/// @brief Class to manage the ArduPilot relay
class AP_Relay {
public:
static AP_Relay create() { return AP_Relay{}; }
constexpr AP_Relay(AP_Relay &&other) = default;
AP_Relay();
/* Do not allow copies */
AP_Relay(const AP_Relay &other) = delete;
@ -43,8 +41,6 @@ public:
static const struct AP_Param::GroupInfo var_info[];
private:
AP_Relay();
AP_Int8 _pin[AP_RELAY_NUM_RELAYS];
AP_Int8 _default;
};