mirror of https://github.com/ArduPilot/ardupilot
AP_SBusOut: 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
076f7bc0cf
commit
dec3a27d91
|
@ -13,22 +13,17 @@
|
||||||
|
|
||||||
class AP_SBusOut {
|
class AP_SBusOut {
|
||||||
public:
|
public:
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
AP_SBusOut();
|
||||||
|
|
||||||
static AP_SBusOut create() {
|
|
||||||
return AP_SBusOut{};
|
|
||||||
}
|
|
||||||
|
|
||||||
constexpr AP_SBusOut(AP_SBusOut &&other) = default;
|
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
AP_SBusOut(const AP_SBusOut &other) = delete;
|
AP_SBusOut(const AP_SBusOut &other) = delete;
|
||||||
AP_SBusOut &operator=(const AP_SBusOut&) = delete;
|
AP_SBusOut &operator=(const AP_SBusOut&) = delete;
|
||||||
|
|
||||||
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
void update();
|
void update();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_SBusOut();
|
|
||||||
AP_HAL::UARTDriver *sbus1_uart;
|
AP_HAL::UARTDriver *sbus1_uart;
|
||||||
|
|
||||||
void init(void);
|
void init(void);
|
||||||
|
|
Loading…
Reference in New Issue