AC_PrecLand: remove unused PrecLandBehaviour enum and accessor

AFAICS this has never been used
This commit is contained in:
Peter Barker 2021-04-14 13:12:31 +10:00 committed by Andrew Tridgell
parent 1ad9542df3
commit 252543978e
2 changed files with 3 additions and 13 deletions

View File

@ -14,8 +14,8 @@ extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
// @Param: ENABLED
// @DisplayName: Precision Land enabled/disabled and behaviour
// @Description: Precision Land enabled/disabled and behaviour
// @DisplayName: Precision Land enabled/disabled
// @Description: Precision Land enabled/disabled
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO_FLAGS("ENABLED", 0, AC_PrecLand, _enabled, 0, AP_PARAM_FLAG_ENABLE),

View File

@ -29,13 +29,6 @@ public:
AC_PrecLand(const AC_PrecLand &other) = delete;
AC_PrecLand &operator=(const AC_PrecLand&) = delete;
// precision landing behaviours (held in PRECLAND_ENABLED parameter)
enum PrecLandBehaviour {
PRECLAND_BEHAVIOUR_DISABLED,
PRECLAND_BEHAVIOR_ALWAYSLAND,
PRECLAND_BEHAVIOR_CAUTIOUS
};
// types of precision landing (used for PRECLAND_TYPE parameter)
enum PrecLandType {
PRECLAND_TYPE_NONE = 0,
@ -94,9 +87,6 @@ private:
KALMAN_FILTER = 1,
};
// returns enabled parameter as an behaviour
enum PrecLandBehaviour get_behaviour() const { return (enum PrecLandBehaviour)(_enabled.get()); }
// run target position estimator
void run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid);
@ -111,7 +101,7 @@ private:
void run_output_prediction();
// parameters
AP_Int8 _enabled; // enabled/disabled and behaviour
AP_Int8 _enabled; // enabled/disabled
AP_Int8 _type; // precision landing sensor type
AP_Int8 _bus; // which sensor bus
AP_Enum<EstimatorType> _estimator_type; // precision landing estimator type