mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: add QRTL always as Q_RTL_MODE option
This commit is contained in:
parent
cc0f850eb9
commit
4f48233b43
|
@ -108,11 +108,17 @@ void ModeRTL::navigate()
|
|||
|
||||
// Switch to QRTL if enabled and within radius
|
||||
bool ModeRTL::switch_QRTL(bool check_loiter_target)
|
||||
{
|
||||
if (!plane.quadplane.available() || (plane.quadplane.rtl_mode != QuadPlane::RTL_MODE::SWITCH_QRTL)) {
|
||||
{
|
||||
if (!plane.quadplane.available() || ((plane.quadplane.rtl_mode != QuadPlane::RTL_MODE::SWITCH_QRTL) && (plane.quadplane.rtl_mode != QuadPlane::RTL_MODE::QRTL_ALWAYS))) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// if Q_RTL_MODE is QRTL always, then immediately switch to QRTL mode
|
||||
if (plane.quadplane.rtl_mode == QuadPlane::RTL_MODE::QRTL_ALWAYS) {
|
||||
plane.set_mode(plane.mode_qrtl, ModeReason::QRTL_INSTEAD_OF_RTL);
|
||||
return true;
|
||||
}
|
||||
|
||||
uint16_t qrtl_radius = abs(plane.g.rtl_radius);
|
||||
if (qrtl_radius == 0) {
|
||||
qrtl_radius = abs(plane.aparm.loiter_radius);
|
||||
|
|
|
@ -195,8 +195,8 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||
|
||||
// @Param: RTL_MODE
|
||||
// @DisplayName: VTOL RTL mode
|
||||
// @Description: If this is set to 1 then an RTL will change to QRTL when within RTL_RADIUS meters of the RTL destination, VTOL approach: vehicle will RTL at RTL alt and circle with a radius of Q_FW_LND_APR_RAD down to Q_RLT_ALT and then transission into the wind and QRTL, see 'AUTO VTOL Landing'
|
||||
// @Values: 0:Disabled,1:Enabled,2:VTOL approach
|
||||
// @Description: If this is set to 1 then an RTL will change to QRTL when within RTL_RADIUS meters of the RTL destination, VTOL approach: vehicle will RTL at RTL alt and circle with a radius of Q_FW_LND_APR_RAD down to Q_RLT_ALT and then transission into the wind and QRTL, see 'AUTO VTOL Landing', QRTL Always: do a QRTL instead of RTL
|
||||
// @Values: 0:Disabled,1:Enabled,2:VTOL approach,3:QRTL Always
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RTL_MODE", 36, QuadPlane, rtl_mode, 0),
|
||||
|
||||
|
|
|
@ -362,6 +362,7 @@ private:
|
|||
NONE,
|
||||
SWITCH_QRTL,
|
||||
VTOL_APPROACH_QRTL,
|
||||
QRTL_ALWAYS,
|
||||
};
|
||||
|
||||
// control if a VTOL GUIDED will be used
|
||||
|
|
Loading…
Reference in New Issue