Skip to content
Snippets Groups Projects
Commit e6c6161e authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

APM: fixed mission reset by setting waypoint to zero

this does a full mission reset (equivalent to rebooting)
parent 8c1766f5
No related branches found
No related tags found
No related merge requests found
......@@ -9,6 +9,7 @@ static void init_commands()
nav_command_ID = NO_COMMAND;
non_nav_command_ID = NO_COMMAND;
next_nav_command.id = CMD_BLANK;
nav_command_index = 0;
}
static void update_auto()
......
......@@ -4,7 +4,15 @@
//----------------------------------------
void change_command(uint8_t cmd_index)
{
struct Location temp = get_cmd_with_index(cmd_index);
struct Location temp;
if (cmd_index == 0) {
init_commands();
gcs_send_text_fmt(PSTR("Received Request - reset mission"));
return;
}
temp = get_cmd_with_index(cmd_index);
if (temp.id > MAV_CMD_NAV_LAST ) {
gcs_send_text_P(SEVERITY_LOW,PSTR("Bad Request - cannot change to non-Nav cmd"));
......
......@@ -39,7 +39,7 @@ static void read_control_switch()
APM_RC.InputCh(g.reset_mission_chan-1) > RESET_SWITCH_CHAN_PWM) {
// reset to first waypoint in mission
prev_WP = current_loc;
change_command(1);
change_command(0);
}
switch_debouncer = false;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment