Browse Source

AP_ADSB: 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
6487a22acd
  1. 14
      libraries/AP_ADSB/AP_ADSB.h

14
libraries/AP_ADSB/AP_ADSB.h

@ -31,12 +31,12 @@ @@ -31,12 +31,12 @@
class AP_ADSB {
public:
static AP_ADSB create(const AP_AHRS &ahrs) {
return AP_ADSB{ahrs};
AP_ADSB(const AP_AHRS &ahrs)
: _ahrs(ahrs)
{
AP_Param::setup_object_defaults(this, var_info);
}
constexpr AP_ADSB(AP_ADSB &&other) = default;
/* Do not allow copies */
AP_ADSB(const AP_ADSB &other) = delete;
AP_ADSB &operator=(const AP_ADSB&) = delete;
@ -76,12 +76,6 @@ public: @@ -76,12 +76,6 @@ public:
void handle_message(const mavlink_channel_t chan, const mavlink_message_t* msg);
private:
AP_ADSB(const AP_AHRS &ahrs)
: _ahrs(ahrs)
{
AP_Param::setup_object_defaults(this, var_info);
}
// initialize _vehicle_list
void init();

Loading…
Cancel
Save