diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 1cb332597dfa97..f77e3cb5b9dc5f 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -3226,6 +3226,71 @@ def FlyMissionTwice(self): self.wait_disarmed() self.delay_sim_time(20) + def FlyMissionTwiceWithReset(self): + '''Fly a mission twice in a row without changing modes in between. + Allow the mission to complete, then reset the mission state machine and restart the mission.''' + + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + + num_wp = self.get_mission_count() + self.set_parameter("AUTO_OPTIONS", 3) + self.change_mode('AUTO') + self.wait_ready_to_arm() + + for i in 1, 2: + self.progress("run %u" % i) + # Use the "Reset Mission" param of DO_SET_MISSION_CURRENT to reset mission state machine + self.set_current_waypoint_using_mav_cmd_do_set_mission_current(seq=0, reset=1) + self.arm_vehicle() + self.wait_waypoint(num_wp-1, num_wp-1) + self.wait_disarmed() + self.delay_sim_time(20) + + def MissionIndexValidity(self): + '''Confirm that attempting to select an invalid mission item is rejected.''' + + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + + num_wp = self.get_mission_count() + accepted_indices = [0, 1, num_wp-1] + denied_indices = [-1, num_wp] + + for seq in accepted_indices: + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT, + p1=seq, + timeout=1, + want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + + for seq in denied_indices: + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT, + p1=seq, + timeout=1, + want_result=mavutil.mavlink.MAV_RESULT_DENIED) + + def InvalidJumpTags(self): + '''Verify the behaviour when selecting invalid jump tags.''' + + MAX_TAG_NUM = 65535 + # Jump tag is not present, so expect FAILED + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_JUMP_TAG, + p1=MAX_TAG_NUM, + timeout=1, + want_result=mavutil.mavlink.MAV_RESULT_FAILED) + + # Jump tag is too big, so expect DENIED + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_JUMP_TAG, + p1=MAX_TAG_NUM+1, + timeout=1, + want_result=mavutil.mavlink.MAV_RESULT_DENIED) + def GPSViconSwitching(self): """Fly GPS and Vicon switching test""" self.customise_SITL_commandline(["--uartF=sim:vicon:"]) @@ -10544,6 +10609,9 @@ def tests2b(self): # this block currently around 9.5mins here self.ThrottleGainBoost, self.ScriptMountPOI, self.FlyMissionTwice, + self.FlyMissionTwiceWithReset, + self.MissionIndexValidity, + self.InvalidJumpTags, self.IMUConsistency, self.AHRSTrimLand, self.GuidedYawRate, diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index ab13d592fc7679..c82dca3c0210e6 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6055,7 +6055,7 @@ def MAV_CMD_DO_SET_MISSION_CURRENT(self, target_sysid=None, target_compid=1): timeout=1, target_sysid=target_sysid, target_compid=target_compid, - want_result=mavutil.mavlink.MAV_RESULT_FAILED, + want_result=mavutil.mavlink.MAV_RESULT_DENIED, ) def FlashStorage(self): diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 543bb6d5d04963..6aa9d1f18a8276 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -5897,10 +5897,12 @@ def run_cmd_get_ack(self, command, want_result, timeout, quiet=False, mav=None, def set_current_waypoint_using_mav_cmd_do_set_mission_current( self, seq, + reset=0, target_sysid=1, target_compid=1): self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT, p1=seq, + p2=reset, timeout=1, target_sysid=target_sysid, target_compid=target_compid) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index a000e7ba91116b..3487d3a974fcaa 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -538,7 +538,7 @@ 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, bool rewind) +bool AP_Mission::set_current_cmd(uint16_t index) { // read command to check for DO_LAND_START Mission_Command cmd; @@ -546,10 +546,8 @@ bool AP_Mission::set_current_cmd(uint16_t index, bool rewind) _flags.in_landing_sequence = false; } - // mission command has been set and not as rewind command, don't track history. - if (!rewind) { - reset_wp_history(); - } + // mission command has been set, don't track history. + reset_wp_history(); // sanity check index and that we have a mission if (index >= (unsigned)_cmd_total || _cmd_total == 1) { diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index e01c372ffa3c16..b50fa4d9822b0b 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -601,7 +601,7 @@ class AP_Mission } // set_current_cmd - jumps to command specified by index - bool set_current_cmd(uint16_t index, bool rewind = false); + bool set_current_cmd(uint16_t index); // restart current navigation command. Used to handle external changes to mission // returns true on success, false if current nav command has been deleted @@ -724,6 +724,8 @@ class AP_Mission // Returns 0 if no appropriate JUMP_TAG match can be found. uint16_t get_index_of_jump_tag(const uint16_t tag) const; + bool is_valid_index(const uint16_t index) const { return index < _cmd_total; } + #if AP_SDCARD_STORAGE_ENABLED bool failed_sdcard_storage(void) const { return _failed_sdcard_storage; diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 7dbd32ef4be56e..897ef275e06ea1 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -639,6 +639,7 @@ class GCS_MAVLINK virtual MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg); virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_do_jump_tag(const mavlink_command_long_t &packet); MAV_RESULT handle_command_battery_reset(const mavlink_command_int_t &packet); void handle_command_long(const mavlink_message_t &msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 371f16a8641a74..19b33b06c56a8e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4452,8 +4452,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_i // the current waypoint, rather than this DO command. It is hoped we // can move to this command in the future to avoid acknowledgement // issues with MISSION_SET_CURRENT -// This also handles DO_JUMP_TAG by converting the tag to an index -// and setting the index as if it was a normal do_set_mission_current MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_command_long_t &packet) { AP_Mission *mission = AP::mission(); @@ -4462,11 +4460,43 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_comm } const uint32_t seq = (uint32_t)packet.param1; - if (packet.command == MAV_CMD_DO_JUMP_TAG) { - if (!mission->jump_to_tag(seq)) { - return MAV_RESULT_FAILED; - } - } else if (!mission->set_current_cmd(seq)) { + if (!mission->is_valid_index(seq)) { + return MAV_RESULT_DENIED; + } + + // From https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_MISSION_CURRENT: + // Param 2: Reset Mission + // - Resets mission. 1: true, 0: false. Resets jump counters to initial values + // and changes mission state "completed" to be "active" or "paused". + const bool reset_and_restart = is_equal(packet.param2, 1.0f); + if (reset_and_restart) { + mission->reset(); + } + if (!mission->set_current_cmd(seq)) { + return MAV_RESULT_FAILED; + } + if (reset_and_restart) { + mission->resume(); + } + + // volunteer the new current waypoint for all listeners + send_message(MSG_CURRENT_WAYPOINT); + + return MAV_RESULT_ACCEPTED; +} + +MAV_RESULT GCS_MAVLINK::handle_command_do_jump_tag(const mavlink_command_long_t &packet) +{ + AP_Mission *mission = AP::mission(); + if (mission == nullptr) { + return MAV_RESULT_UNSUPPORTED; + } + + const uint32_t tag = (uint32_t)packet.param1; + if (tag > UINT16_MAX) { + return MAV_RESULT_DENIED; + } + if (!mission->jump_to_tag(tag)) { return MAV_RESULT_FAILED; } @@ -4735,6 +4765,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t #endif case MAV_CMD_DO_JUMP_TAG: + result = handle_command_do_jump_tag(packet); + break; + case MAV_CMD_DO_SET_MISSION_CURRENT: result = handle_command_do_set_mission_current(packet); break;