AP_Volz_Protocol: 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:15 +11:00
parent d175fb2f18
commit 15026c6898

View File

@ -50,22 +50,17 @@
class AP_Volz_Protocol {
public:
static const struct AP_Param::GroupInfo var_info[];
static AP_Volz_Protocol create() {
return AP_Volz_Protocol{};
}
constexpr AP_Volz_Protocol(AP_Volz_Protocol &&other) = default;
AP_Volz_Protocol();
/* Do not allow copies */
AP_Volz_Protocol(const AP_Volz_Protocol &other) = delete;
AP_Volz_Protocol &operator=(const AP_Volz_Protocol&) = delete;
static const struct AP_Param::GroupInfo var_info[];
void update();
private:
AP_Volz_Protocol();
AP_HAL::UARTDriver *port;
void init(void);