ArduPlane: Use auto enable and auto disable from AC_Fence

This commit is contained in:
James O'Shannessy 2021-01-14 10:36:42 +11:00 committed by Peter Barker
parent b6d29d746b
commit 8a99d9dd00
4 changed files with 5 additions and 21 deletions

View File

@ -929,7 +929,6 @@ private:
// fence.cpp
void fence_check();
bool fence_stickmixing() const;
void disable_fence_for_landing(void);
#endif
// ArduPlane.cpp

View File

@ -383,7 +383,7 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd)
}
#if AC_FENCE == ENABLED
disable_fence_for_landing();
plane.fence.auto_disable_fence_for_landing();
#endif
}

View File

@ -127,21 +127,4 @@ bool Plane::fence_stickmixing(void) const
return true;
}
void Plane::disable_fence_for_landing(void)
{
switch (fence.auto_enabled()) {
case AC_Fence::AutoEnable::ALWAYS_ENABLED:
fence.enable(false);
gcs().send_text(MAV_SEVERITY_NOTICE, "Fence disabled (auto disable)");
break;
case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY:
fence.disable_floor();
gcs().send_text(MAV_SEVERITY_NOTICE, "Fence floor disabled (auto disable)");
break;
default:
// fence does not auto-disable in other landing conditions
break;
}
}
#endif

View File

@ -1307,7 +1307,7 @@ void QuadPlane::init_qland(void)
plane.g2.landing_gear.deploy_for_landing();
#endif
#if AC_FENCE == ENABLED
plane.disable_fence_for_landing();
plane.fence.auto_disable_fence_for_landing();
#endif
}
@ -3051,7 +3051,9 @@ bool QuadPlane::verify_vtol_land(void)
if (poscontrol.state == QPOS_POSITION2 &&
plane.auto_state.wp_distance < 2) {
poscontrol.state = QPOS_LAND_DESCEND;
plane.disable_fence_for_landing();
#if AC_FENCE == ENABLED
plane.fence.auto_disable_fence_for_landing();
#endif
#if LANDING_GEAR_ENABLED == ENABLED
plane.g2.landing_gear.deploy_for_landing();
#endif