AP_Rally: 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:13 +11:00
parent e798b38271
commit 7122cae589

View File

@ -36,11 +36,7 @@ struct PACKED RallyLocation {
/// @brief Object managing Rally Points
class AP_Rally {
public:
static AP_Rally create(AP_AHRS &ahrs) {
return AP_Rally{ahrs};
}
constexpr AP_Rally(AP_Rally &&other) = default;
AP_Rally(AP_AHRS &ahrs);
/* Do not allow copies */
AP_Rally(const AP_Rally &other) = delete;
@ -66,9 +62,6 @@ public:
// parameter block
static const struct AP_Param::GroupInfo var_info[];
protected:
AP_Rally(AP_AHRS &ahrs);
private:
virtual bool is_valid(const Location &rally_point) const { return true; }