mirror of https://github.com/ArduPilot/ardupilot
AC_PrecLand: Allow fast descend
This commit is contained in:
parent
cc25f2915a
commit
d5a5f4f863
|
@ -178,7 +178,7 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
|
|||
// @Param: OPTIONS
|
||||
// @DisplayName: Precision Landing Extra Options
|
||||
// @Description: Precision Landing Extra Options
|
||||
// @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition
|
||||
// @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition, 2: Do not slow vertical speed in final descend phase
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OPTIONS", 17, AC_PrecLand, _options, 0),
|
||||
|
||||
|
|
|
@ -114,6 +114,7 @@ public:
|
|||
AC_PrecLand_StateMachine::RetryAction get_retry_behaviour() const { return static_cast<AC_PrecLand_StateMachine::RetryAction>(_retry_behave.get()); }
|
||||
|
||||
bool allow_precland_after_reposition() const { return _options & PLND_OPTION_PRECLAND_AFTER_REPOSITION; }
|
||||
bool do_fast_descend() const {return _options & PLND_OPTION_FAST_DESCEND; }
|
||||
|
||||
// parameter var table
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
@ -145,6 +146,7 @@ private:
|
|||
PLND_OPTION_DISABLED = 0,
|
||||
PLND_OPTION_MOVING_TARGET = (1 << 0),
|
||||
PLND_OPTION_PRECLAND_AFTER_REPOSITION = (1 << 1),
|
||||
PLND_OPTION_FAST_DESCEND = (1 << 2),
|
||||
};
|
||||
|
||||
// check the status of the target
|
||||
|
|
Loading…
Reference in New Issue