mirror of https://github.com/ArduPilot/ardupilot
Copter: Allow fast descend while Prec Landing
This commit is contained in:
parent
d5a5f4f863
commit
8a1fa0e096
|
@ -666,7 +666,7 @@ void Mode::land_run_vertical_control(bool pause_descent)
|
|||
// doing precland but too far away from the obstacle
|
||||
// do not descend
|
||||
cmb_rate = 0.0f;
|
||||
} else if (target_pos_meas.z > 35.0f && target_pos_meas.z < 200.0f) {
|
||||
} else if (target_pos_meas.z > 35.0f && target_pos_meas.z < 200.0f && !copter.precland.do_fast_descend()) {
|
||||
// very close to the ground and doing prec land, lets slow down to make sure we land on target
|
||||
// compute desired descent velocity
|
||||
const float precland_acceptable_error_cm = 15.0f;
|
||||
|
|
|
@ -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, 2: Do not slow vertical speed in final descend phase
|
||||
// @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition, 2: Maintain high speed in final descent
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OPTIONS", 17, AC_PrecLand, _options, 0),
|
||||
|
||||
|
|
|
@ -114,7 +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; }
|
||||
bool do_fast_descend() const { return _options & PLND_OPTION_FAST_DESCEND; }
|
||||
|
||||
// parameter var table
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
|
Loading…
Reference in New Issue