Plane: allow for continue after land for quadplanes

this allows for a new takeoff after a quadplane auto landing
This commit is contained in:
Andrew Tridgell 2020-03-04 14:59:05 +11:00 committed by Randy Mackay
parent d9d53d380d
commit 568e13fbb9
2 changed files with 15 additions and 5 deletions

View File

@ -2781,19 +2781,26 @@ bool QuadPlane::land_detector(uint32_t timeout_ms)
/* /*
check if a landing is complete check if a landing is complete
*/ */
void QuadPlane::check_land_complete(void) bool QuadPlane::check_land_complete(void)
{ {
if (poscontrol.state != QPOS_LAND_FINAL) { if (poscontrol.state != QPOS_LAND_FINAL) {
// only apply to final landing phase // only apply to final landing phase
return; return false;
} }
if (land_detector(4000)) { if (land_detector(4000)) {
plane.arming.disarm(AP_Arming::Method::LANDED);
poscontrol.state = QPOS_LAND_COMPLETE; poscontrol.state = QPOS_LAND_COMPLETE;
gcs().send_text(MAV_SEVERITY_INFO,"Land complete"); gcs().send_text(MAV_SEVERITY_INFO,"Land complete");
// reload target airspeed which could have been modified by the mission // reload target airspeed which could have been modified by the mission
plane.aparm.airspeed_cruise_cm.load(); plane.aparm.airspeed_cruise_cm.load();
if (plane.control_mode != &plane.mode_auto ||
!plane.mission.continue_after_land()) {
// disarm on land unless we have MIS_OPTIONS setup to
// continue after land in AUTO
plane.arming.disarm(AP_Arming::Method::LANDED);
} }
return true;
}
return false;
} }
@ -2858,7 +2865,10 @@ bool QuadPlane::verify_vtol_land(void)
gcs().send_text(MAV_SEVERITY_INFO,"Land final started"); gcs().send_text(MAV_SEVERITY_INFO,"Land final started");
} }
check_land_complete(); if (check_land_complete() && plane.mission.continue_after_land()) {
gcs().send_text(MAV_SEVERITY_INFO,"Mission continue");
return true;
}
return false; return false;
} }

View File

@ -235,7 +235,7 @@ private:
void init_loiter(void); void init_loiter(void);
void init_qland(void); void init_qland(void);
void control_loiter(void); void control_loiter(void);
void check_land_complete(void); bool check_land_complete(void);
bool land_detector(uint32_t timeout_ms); bool land_detector(uint32_t timeout_ms);
bool check_land_final(void); bool check_land_final(void);