From 3f37cce6c75859eb69bde078c9517da6d3a3d307 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 18 Sep 2011 12:17:58 +1000 Subject: [PATCH] remove unused MESSAGE_COMMAND_LIST --- ArduPlane/commands.pde | 1 - ArduPlane/commands_process.pde | 3 --- ArduPlane/defines.h | 1 - ArduPlane/system.pde | 6 ------ 4 files changed, 11 deletions(-) diff --git a/ArduPlane/commands.pde b/ArduPlane/commands.pde index 0ad04ee3da..f40b14f2b0 100644 --- a/ArduPlane/commands.pde +++ b/ArduPlane/commands.pde @@ -138,7 +138,6 @@ static void set_next_WP(struct Location *wp) //gcs.send_text_P(SEVERITY_LOW,PSTR("load WP")); SendDebug_P("MSG - wp_index: "); SendDebugln(g.waypoint_index, DEC); - gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index); // copy the current WP into the OldWP slot // --------------------------------------- diff --git a/ArduPlane/commands_process.pde b/ArduPlane/commands_process.pde index c0b2576e92..719747bd13 100644 --- a/ArduPlane/commands_process.pde +++ b/ArduPlane/commands_process.pde @@ -118,7 +118,6 @@ static void process_next_command() static void process_must() { gcs.send_text_P(SEVERITY_LOW,PSTR("New cmd: ")); - gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index); // clear May indexes command_may_index = NO_COMMAND; @@ -135,7 +134,6 @@ static void process_must() static void process_may() { gcs.send_text_P(SEVERITY_LOW,PSTR("")); - gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index); command_may_ID = next_command.id; handle_process_may(); @@ -154,6 +152,5 @@ static void process_now() next_command.id = NO_COMMAND; gcs.send_text(SEVERITY_LOW, ""); - gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index); } diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 7d0aac6c2b..7d1a3b9603 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -123,7 +123,6 @@ #define MSG_COMMAND_REQUEST 0x20 #define MSG_COMMAND_UPLOAD 0x21 -#define MSG_COMMAND_LIST 0x22 #define MSG_COMMAND_MODE_CHANGE 0x23 #define MSG_CURRENT_WAYPOINT 0x24 diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index b7893a821c..eb7f7e02d4 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -272,12 +272,6 @@ static void startup_ground(void) delay(GROUND_START_DELAY * 1000); #endif - // Output waypoints for confirmation - // -------------------------------- - for(int i = 1; i < g.waypoint_total + 1; i++) { - gcs.send_message(MSG_COMMAND_LIST, i); - } - // Makes the servos wiggle // step 1 = 1 wiggle // -----------------------