diff --git a/libraries/AP_Rally/AP_Rally.h b/libraries/AP_Rally/AP_Rally.h index ba9a20dd6c..15482e7374 100644 --- a/libraries/AP_Rally/AP_Rally.h +++ b/libraries/AP_Rally/AP_Rally.h @@ -35,9 +35,16 @@ struct PACKED RallyLocation { /// @class AP_Rally /// @brief Object managing Rally Points class AP_Rally { - public: - AP_Rally(AP_AHRS &ahrs); + static AP_Rally create(AP_AHRS &ahrs) { + return AP_Rally{ahrs}; + } + + constexpr AP_Rally(AP_Rally &&other) = default; + + /* Do not allow copies */ + AP_Rally(const AP_Rally &other) = delete; + AP_Rally &operator=(const AP_Rally&) = delete; // data handling bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const; @@ -46,7 +53,7 @@ public: uint8_t get_rally_max(void) const { return _storage.size() / AP_RALLY_WP_SIZE; } float get_rally_limit_km() const { return _rally_limit_km; } - + Location rally_location_to_location(const RallyLocation &ret) const; // logic handling @@ -59,6 +66,9 @@ 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; }