mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: send current wp as 65535 to GCS when mission complete
This commit is contained in:
parent
c7ffd2db90
commit
36af34bf8b
@ -538,9 +538,13 @@ static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
|
||||
|
||||
static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_mission_current_send(
|
||||
chan,
|
||||
(uint16_t)mission.get_current_nav_cmd().index);
|
||||
uint16_t current_cmd_index;
|
||||
if (mission.state() == AP_Mission::MISSION_RUNNING) {
|
||||
current_cmd_index = mission.get_current_nav_cmd().index;
|
||||
}else{
|
||||
current_cmd_index = AP_MISSION_CMD_INDEX_NONE;
|
||||
}
|
||||
mavlink_msg_mission_current_send(chan, current_cmd_index);
|
||||
}
|
||||
|
||||
static void NOINLINE send_statustext(mavlink_channel_t chan)
|
||||
|
Loading…
Reference in New Issue
Block a user