Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Qplane auto disarm #6475

Closed
wants to merge 1 commit into from
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 13 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2157,11 +2157,23 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
*/
void QuadPlane::check_land_complete(void)
{
const uint32_t now = AP_HAL::millis();

if (poscontrol.state == QPOS_LAND_COMPLETE &&
plane.arming.is_armed() &&
plane.landing.get_disarm_delay() > 0 &&
now - landing_detect.lower_limit_start_ms >= plane.landing.get_disarm_delay()*1000UL) {
// disarm after user-defined delay
if (plane.disarm_motors()) {
gcs().send_text(MAV_SEVERITY_INFO,"Auto disarmed");
}
}

if (poscontrol.state != QPOS_LAND_FINAL) {
// only apply to final landing phase
return;
}
const uint32_t now = AP_HAL::millis();

bool might_be_landed = (landing_detect.lower_limit_start_ms != 0 &&
now - landing_detect.lower_limit_start_ms > 1000);
if (!might_be_landed) {
Expand Down Expand Up @@ -2190,7 +2202,6 @@ void QuadPlane::check_land_complete(void)
landing_detect.land_start_ms = 0;
// motors have been at zero for 5s, and we have had less than 0.3m
// change in altitude for last 4s. We are landed.
plane.disarm_motors();
poscontrol.state = QPOS_LAND_COMPLETE;
gcs().send_text(MAV_SEVERITY_INFO,"Land complete");
// reload target airspeed which could have been modified by the mission
Expand Down