APM: report throttle and ground speed mission changes

This commit is contained in:
Andrew Tridgell 2012-09-12 13:09:32 +10:00
parent 972b8df052
commit 4a942bc45d
1 changed files with 4 additions and 1 deletions

View File

@ -550,12 +550,15 @@ static void do_change_speed()
}
break;
case 1: // Ground speed
gcs_send_text_fmt(PSTR("Set groundspeed %u"), (unsigned)next_nonnav_command.alt);
g.min_gndspeed_cm.set(next_nonnav_command.alt * 100);
break;
}
if(next_nonnav_command.lat > 0)
if (next_nonnav_command.lat > 0) {
gcs_send_text_fmt(PSTR("Set throttle %u"), (unsigned)next_nonnav_command.lat);
g.throttle_cruise.set(next_nonnav_command.lat);
}
}
static void do_set_home()