diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 897cf1526d..b006e08b50 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -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 + // @Bitmask: 0:Clear Mission on reboot, 1:Use distance to land calc on battery failsafe // @User: Advanced AP_GROUPINFO("OPTIONS", 2, AP_Mission, _options, AP_MISSION_OPTIONS_DEFAULT), @@ -176,6 +176,7 @@ void AP_Mission::reset() _flags.nav_cmd_loaded = false; _flags.do_cmd_loaded = false; _flags.do_cmd_all_done = false; + _flags.in_landing_sequence = false; _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE; _do_cmd.index = AP_MISSION_CMD_INDEX_NONE; _prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE; @@ -282,6 +283,11 @@ bool AP_Mission::verify_command(const Mission_Command& cmd) bool AP_Mission::start_command(const Mission_Command& cmd) { + // check for landing related commands and set in_landing_sequence flag + if (is_landing_type_cmd(cmd.id) || cmd.id == MAV_CMD_DO_LAND_START) { + set_in_landing_sequence_flag(true); + } + gcs().send_text(MAV_SEVERITY_INFO, "Mission: %u %s", cmd.index, cmd.type()); switch (cmd.id) { case MAV_CMD_DO_GRIPPER: @@ -391,6 +397,12 @@ int32_t AP_Mission::get_next_ground_course_cd(int32_t default_angle) // set_current_cmd - jumps to command specified by index bool AP_Mission::set_current_cmd(uint16_t index) { + // read command to check for DO_LAND_START + Mission_Command cmd; + if (!read_cmd_from_storage(index, cmd) || (cmd.id != MAV_CMD_DO_LAND_START)) { + _flags.in_landing_sequence = false; + } + // sanity check index and that we have a mission if (index >= (unsigned)_cmd_total || _cmd_total == 1) { return false; @@ -422,7 +434,6 @@ bool AP_Mission::set_current_cmd(uint16_t index) // search until we find next nav command or reach end of command list while (!_flags.nav_cmd_loaded) { // get next command - Mission_Command cmd; if (!get_next_cmd(index, cmd, true)) { _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE; return false; @@ -1460,6 +1471,7 @@ void AP_Mission::complete() { // flag mission as complete _flags.state = MISSION_COMPLETE; + _flags.in_landing_sequence = false; // callback to main program's mission complete function _mission_complete_fn(); @@ -1583,7 +1595,7 @@ void AP_Mission::advance_current_do_cmd() /// returns true if found, false if not found (i.e. mission complete) /// accounts for do_jump commands /// increment_jump_num_times_if_found should be set to true if advancing the active navigation command -bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool increment_jump_num_times_if_found) +bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool increment_jump_num_times_if_found, bool send_gcs_msg) { uint16_t cmd_index = start_index; Mission_Command temp_cmd; @@ -1633,7 +1645,7 @@ bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool i if (jump_times_run < temp_cmd.content.jump.num_times) { // update the record of the number of times run if (increment_jump_num_times_if_found) { - increment_jump_times_run(temp_cmd); + increment_jump_times_run(temp_cmd, send_gcs_msg); } // continue searching from jump target cmd_index = temp_cmd.content.jump.target; @@ -1720,7 +1732,7 @@ int16_t AP_Mission::get_jump_times_run(const Mission_Command& cmd) } /// increment_jump_times_run - increments the recorded number of times the jump command has been run -void AP_Mission::increment_jump_times_run(Mission_Command& cmd) +void AP_Mission::increment_jump_times_run(Mission_Command& cmd, bool send_gcs_msg) { // exit immediately if cmd is not a do-jump command if (cmd.id != MAV_CMD_DO_JUMP) { @@ -1732,7 +1744,9 @@ void AP_Mission::increment_jump_times_run(Mission_Command& cmd) for (uint8_t i=0; i= dist_continue_to_land) { + // then the mission should carry on uninterrupted as that is the shorter distance + gcs().send_text(MAV_SEVERITY_NOTICE, "Rejecting RTL: closer land if mis continued"); + return true; + } else { + // allow failsafes to interrupt the current mission + return false; + } +} + +// Approximate the distance travelled to get to a landing. DO_JUMP commands are observed in look forward. +bool AP_Mission::distance_to_landing(uint16_t index, float &tot_distance, Location prev_loc) +{ + Mission_Command temp_cmd; + tot_distance = 0.0f; + bool ret; + + // back up jump tracking to reset after distance calculation + jump_tracking_struct _jump_tracking_backup[AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS]; + for (uint8_t i=0; i