Browse Source

AP_ServoRelayEvents: 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
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
1cdbb09466
  1. 26
      libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.h

26
libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.h

@ -11,12 +11,18 @@ @@ -11,12 +11,18 @@
class AP_ServoRelayEvents {
public:
static AP_ServoRelayEvents create(AP_Relay &_relay) {
return AP_ServoRelayEvents{_relay};
AP_ServoRelayEvents(AP_Relay &_relay)
: relay(_relay)
, mask(0)
, type(EVENT_TYPE_RELAY)
, start_time_ms(0)
, delay_ms(0)
, repeat(0)
, channel(0)
, servo_value(0)
{
}
constexpr AP_ServoRelayEvents(AP_ServoRelayEvents &&other) = default;
/* Do not allow copies */
AP_ServoRelayEvents(const AP_ServoRelayEvents &other) = delete;
AP_ServoRelayEvents &operator=(const AP_ServoRelayEvents&) = delete;
@ -31,18 +37,6 @@ public: @@ -31,18 +37,6 @@ public:
void update_events(void);
private:
AP_ServoRelayEvents(AP_Relay &_relay)
: relay(_relay)
, mask(0)
, type(EVENT_TYPE_RELAY)
, start_time_ms(0)
, delay_ms(0)
, repeat(0)
, channel(0)
, servo_value(0)
{
}
AP_Relay &relay;
uint16_t mask;

Loading…
Cancel
Save