mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
APM: show waypoint number in jump message
This commit is contained in:
parent
92bdc23ab6
commit
ff6301fb46
@ -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"),
|
||||||
|
(unsigned)next_nonnav_command.p1,
|
||||||
|
(int)next_nonnav_command.lat);
|
||||||
if (next_nonnav_command.lat > 0) {
|
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;
|
||||||
|
Loading…
Reference in New Issue
Block a user