mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
remove unused MESSAGE_COMMAND_LIST
This commit is contained in:
parent
9baab490f1
commit
3f37cce6c7
@ -138,7 +138,6 @@ static void set_next_WP(struct Location *wp)
|
|||||||
//gcs.send_text_P(SEVERITY_LOW,PSTR("load WP"));
|
//gcs.send_text_P(SEVERITY_LOW,PSTR("load WP"));
|
||||||
SendDebug_P("MSG - wp_index: ");
|
SendDebug_P("MSG - wp_index: ");
|
||||||
SendDebugln(g.waypoint_index, DEC);
|
SendDebugln(g.waypoint_index, DEC);
|
||||||
gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index);
|
|
||||||
|
|
||||||
// copy the current WP into the OldWP slot
|
// copy the current WP into the OldWP slot
|
||||||
// ---------------------------------------
|
// ---------------------------------------
|
||||||
|
@ -118,7 +118,6 @@ static void process_next_command()
|
|||||||
static void process_must()
|
static void process_must()
|
||||||
{
|
{
|
||||||
gcs.send_text_P(SEVERITY_LOW,PSTR("New cmd: <process_must>"));
|
gcs.send_text_P(SEVERITY_LOW,PSTR("New cmd: <process_must>"));
|
||||||
gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index);
|
|
||||||
|
|
||||||
// clear May indexes
|
// clear May indexes
|
||||||
command_may_index = NO_COMMAND;
|
command_may_index = NO_COMMAND;
|
||||||
@ -135,7 +134,6 @@ static void process_must()
|
|||||||
static void process_may()
|
static void process_may()
|
||||||
{
|
{
|
||||||
gcs.send_text_P(SEVERITY_LOW,PSTR("<process_may>"));
|
gcs.send_text_P(SEVERITY_LOW,PSTR("<process_may>"));
|
||||||
gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index);
|
|
||||||
|
|
||||||
command_may_ID = next_command.id;
|
command_may_ID = next_command.id;
|
||||||
handle_process_may();
|
handle_process_may();
|
||||||
@ -154,6 +152,5 @@ static void process_now()
|
|||||||
next_command.id = NO_COMMAND;
|
next_command.id = NO_COMMAND;
|
||||||
|
|
||||||
gcs.send_text(SEVERITY_LOW, "<process_now>");
|
gcs.send_text(SEVERITY_LOW, "<process_now>");
|
||||||
gcs.send_message(MSG_COMMAND_LIST, g.waypoint_index);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -123,7 +123,6 @@
|
|||||||
|
|
||||||
#define MSG_COMMAND_REQUEST 0x20
|
#define MSG_COMMAND_REQUEST 0x20
|
||||||
#define MSG_COMMAND_UPLOAD 0x21
|
#define MSG_COMMAND_UPLOAD 0x21
|
||||||
#define MSG_COMMAND_LIST 0x22
|
|
||||||
#define MSG_COMMAND_MODE_CHANGE 0x23
|
#define MSG_COMMAND_MODE_CHANGE 0x23
|
||||||
#define MSG_CURRENT_WAYPOINT 0x24
|
#define MSG_CURRENT_WAYPOINT 0x24
|
||||||
|
|
||||||
|
@ -272,12 +272,6 @@ static void startup_ground(void)
|
|||||||
delay(GROUND_START_DELAY * 1000);
|
delay(GROUND_START_DELAY * 1000);
|
||||||
#endif
|
#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
|
// Makes the servos wiggle
|
||||||
// step 1 = 1 wiggle
|
// step 1 = 1 wiggle
|
||||||
// -----------------------
|
// -----------------------
|
||||||
|
Loading…
Reference in New Issue
Block a user