Browse Source

AC_PrecLand: add static create method

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
b29a183a74
  1. 14
      libraries/AC_PrecLand/AC_PrecLand.h

14
libraries/AC_PrecLand/AC_PrecLand.h

@ -25,7 +25,6 @@ class AC_PrecLand
friend class AC_PrecLand_SITL; friend class AC_PrecLand_SITL;
public: public:
// precision landing behaviours (held in PRECLAND_ENABLED parameter) // precision landing behaviours (held in PRECLAND_ENABLED parameter)
enum PrecLandBehaviour { enum PrecLandBehaviour {
PRECLAND_BEHAVIOUR_DISABLED, PRECLAND_BEHAVIOUR_DISABLED,
@ -42,8 +41,15 @@ public:
PRECLAND_TYPE_SITL, PRECLAND_TYPE_SITL,
}; };
// constructor static AC_PrecLand create(const AP_AHRS& ahrs, const AP_InertialNav& inav) {
AC_PrecLand(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 // perform any required initialisation of landing controllers
void init(); void init();
@ -79,6 +85,8 @@ public:
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
private: private:
AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav);
enum estimator_type_t { enum estimator_type_t {
ESTIMATOR_TYPE_RAW_SENSOR = 0, ESTIMATOR_TYPE_RAW_SENSOR = 0,
ESTIMATOR_TYPE_KALMAN_FILTER = 1 ESTIMATOR_TYPE_KALMAN_FILTER = 1

Loading…
Cancel
Save