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

Added MIS_OPTIONS bit for continue after land #13721

Merged
merged 4 commits into from
Jun 2, 2020
Merged
Show file tree
Hide file tree
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
10 changes: 10 additions & 0 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1521,6 +1521,16 @@ bool ModeAuto::verify_land()
case State::Descending:
// rely on THROTTLE_LAND mode to correctly update landing status
retval = copter.ap.land_complete && (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE);
if (retval && !mission.continue_after_land() && copter.motors->armed()) {
rmackay9 marked this conversation as resolved.
Show resolved Hide resolved
/*
we want to stop mission processing on land
completion. Disarm now, then return false. This
leaves mission state machine in the current NAV_LAND
mission item. After disarming the mission will reset
*/
copter.arming.disarm(AP_Arming::Method::LANDED);
retval = false;
}
break;

default:
Expand Down
18 changes: 14 additions & 4 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2781,19 +2781,26 @@ bool QuadPlane::land_detector(uint32_t timeout_ms)
/*
check if a landing is complete
*/
void QuadPlane::check_land_complete(void)
bool QuadPlane::check_land_complete(void)
{
if (poscontrol.state != QPOS_LAND_FINAL) {
// only apply to final landing phase
return;
return false;
}
if (land_detector(4000)) {
plane.arming.disarm(AP_Arming::Method::LANDED);
poscontrol.state = QPOS_LAND_COMPLETE;
gcs().send_text(MAV_SEVERITY_INFO,"Land complete");
// reload target airspeed which could have been modified by the mission
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;
}


Expand Down Expand Up @@ -2858,7 +2865,10 @@ bool QuadPlane::verify_vtol_land(void)
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;
}

Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -235,7 +235,7 @@ class QuadPlane
void init_loiter(void);
void init_qland(void);
void control_loiter(void);
void check_land_complete(void);
bool check_land_complete(void);
bool land_detector(uint32_t timeout_ms);
bool check_land_final(void);

Expand Down
14 changes: 13 additions & 1 deletion libraries/AP_Landing/AP_Landing_Slope.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,12 +89,13 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
const bool below_flare_sec = (flare_sec > 0 && height <= sink_rate * flare_sec);
const bool probably_crashed = (aparm.crash_detection_enable && fabsf(sink_rate) < 0.2f && !is_flying);

const AP_GPS &gps = AP::gps();

if ((on_approach_stage && below_flare_alt) ||
(on_approach_stage && below_flare_sec && (wp_proportion > 0.5)) ||
(!rangefinder_state_in_range && wp_proportion >= 1) ||
probably_crashed) {

const AP_GPS &gps = AP::gps();
if (type_slope_stage != SLOPE_STAGE_FINAL) {
type_slope_flags.post_stats = true;
if (is_flying && (AP_HAL::millis()-last_flying_ms) > 3000) {
Expand Down Expand Up @@ -156,6 +157,17 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
disarm_if_autoland_complete_fn();
}

if (mission.continue_after_land() &&
type_slope_stage == SLOPE_STAGE_FINAL &&
gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
gps.ground_speed() < 1) {
/*
user has requested to continue with mission after a
landing. Return true to allow for continue
*/
return true;
}

/*
we return false as a landing mission item never completes

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Mission/AP_Mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_Mission::var_info[] = {
// @Param: OPTIONS
// @DisplayName: Mission options bitmask
// @Description: Bitmask of what options to use in missions.
// @Bitmask: 0:Clear Mission on reboot, 1:Use distance to land calc on battery failsafe
// @Bitmask: 0:Clear Mission on reboot, 1:Use distance to land calc on battery failsafe,2:ContinueAfterLand
// @User: Advanced
AP_GROUPINFO("OPTIONS", 2, AP_Mission, _options, AP_MISSION_OPTIONS_DEFAULT),

Expand Down
10 changes: 10 additions & 0 deletions libraries/AP_Mission/AP_Mission.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#define AP_MISSION_OPTIONS_DEFAULT 0 // Do not clear the mission when rebooting
#define AP_MISSION_MASK_MISSION_CLEAR (1<<0) // If set then Clear the mission on boot
#define AP_MISSION_MASK_DIST_TO_LAND_CALC (1<<1) // Allow distance to best landing calculation to be run on failsafe
#define AP_MISSION_MASK_CONTINUE_AFTER_LAND (1<<2) // Allow mission to continue after land

#define AP_MISSION_MAX_WP_HISTORY 7 // The maximum number of previous wp commands that will be stored from the active missions history
#define LAST_WP_PASSED (AP_MISSION_MAX_WP_HISTORY-2)
Expand Down Expand Up @@ -547,6 +548,15 @@ class AP_Mission
// reset the mission history to prevent recalling previous mission histories when restarting missions.
void reset_wp_history(void);

/*
return true if MIS_OPTIONS is set to allow continue of mission
logic after a land. If this is false then after a landing is
complete the vehicle should disarm and mission logic should stop
*/
bool continue_after_land(void) const {
return (_options.get() & AP_MISSION_MASK_CONTINUE_AFTER_LAND) != 0;
}

// user settable parameters
static const struct AP_Param::GroupInfo var_info[];

Expand Down