mirror of https://github.com/ArduPilot/ardupilot
AC_PrecLand: add static create method
This commit is contained in:
parent
cf6ea9642e
commit
b29a183a74
|
@ -25,7 +25,6 @@ class AC_PrecLand
|
|||
friend class AC_PrecLand_SITL;
|
||||
|
||||
public:
|
||||
|
||||
// precision landing behaviours (held in PRECLAND_ENABLED parameter)
|
||||
enum PrecLandBehaviour {
|
||||
PRECLAND_BEHAVIOUR_DISABLED,
|
||||
|
@ -42,8 +41,15 @@ public:
|
|||
PRECLAND_TYPE_SITL,
|
||||
};
|
||||
|
||||
// constructor
|
||||
AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav);
|
||||
static AC_PrecLand create(const AP_AHRS& ahrs, const AP_InertialNav& inav) {
|
||||
return AC_PrecLand{ahrs, inav};
|
||||
}
|
||||
|
||||
constexpr AC_PrecLand(AC_PrecLand &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
AC_PrecLand(const AC_PrecLand &other) = delete;
|
||||
AC_PrecLand &operator=(const AC_PrecLand&) = delete;
|
||||
|
||||
// perform any required initialisation of landing controllers
|
||||
void init();
|
||||
|
@ -79,6 +85,8 @@ public:
|
|||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav);
|
||||
|
||||
enum estimator_type_t {
|
||||
ESTIMATOR_TYPE_RAW_SENSOR = 0,
|
||||
ESTIMATOR_TYPE_KALMAN_FILTER = 1
|
||||
|
|
Loading…
Reference in New Issue