mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
APM: show waypoint number in jump message
This commit is contained in:
parent
c525b6b997
commit
dd17302def
@ -487,9 +487,10 @@ static void do_loiter_at_location()
|
|||||||
static void do_jump()
|
static void do_jump()
|
||||||
{
|
{
|
||||||
struct Location temp;
|
struct Location temp;
|
||||||
gcs_send_text_fmt(PSTR("In jump. Jumps left: %i"),next_nonnav_command.lat);
|
gcs_send_text_fmt(PSTR("Jump to WP %u. Jumps left: %d"),
|
||||||
if(next_nonnav_command.lat > 0) {
|
(unsigned)next_nonnav_command.p1,
|
||||||
|
(int)next_nonnav_command.lat);
|
||||||
|
if (next_nonnav_command.lat > 0) {
|
||||||
nav_command_ID = NO_COMMAND;
|
nav_command_ID = NO_COMMAND;
|
||||||
next_nav_command.id = NO_COMMAND;
|
next_nav_command.id = NO_COMMAND;
|
||||||
non_nav_command_ID = NO_COMMAND;
|
non_nav_command_ID = NO_COMMAND;
|
||||||
@ -498,7 +499,7 @@ static void do_jump()
|
|||||||
temp.lat = next_nonnav_command.lat - 1; // Decrement repeat counter
|
temp.lat = next_nonnav_command.lat - 1; // Decrement repeat counter
|
||||||
|
|
||||||
set_cmd_with_index(temp, g.command_index);
|
set_cmd_with_index(temp, g.command_index);
|
||||||
gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1);
|
gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1);
|
||||||
g.command_index.set_and_save(next_nonnav_command.p1 - 1);
|
g.command_index.set_and_save(next_nonnav_command.p1 - 1);
|
||||||
nav_command_index = next_nonnav_command.p1 - 1;
|
nav_command_index = next_nonnav_command.p1 - 1;
|
||||||
next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump
|
next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump
|
||||||
@ -506,7 +507,7 @@ static void do_jump()
|
|||||||
} else if (next_nonnav_command.lat == -1) { // A repeat count of -1 = repeat forever
|
} else if (next_nonnav_command.lat == -1) { // A repeat count of -1 = repeat forever
|
||||||
nav_command_ID = NO_COMMAND;
|
nav_command_ID = NO_COMMAND;
|
||||||
non_nav_command_ID = NO_COMMAND;
|
non_nav_command_ID = NO_COMMAND;
|
||||||
gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1);
|
gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1);
|
||||||
g.command_index.set_and_save(next_nonnav_command.p1 - 1);
|
g.command_index.set_and_save(next_nonnav_command.p1 - 1);
|
||||||
nav_command_index = next_nonnav_command.p1 - 1;
|
nav_command_index = next_nonnav_command.p1 - 1;
|
||||||
next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump
|
next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump
|
||||||
|
Loading…
Reference in New Issue
Block a user