GCS_Common: clarify enumeration item name MSG_NEXT_WAYPOINT

This commit is contained in:
Peter Barker 2019-01-16 11:21:27 +11:00 committed by Andrew Tridgell
parent da1ded7cb9
commit 8e19e805c6
3 changed files with 8 additions and 8 deletions

View File

@ -436,7 +436,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
waypoint_receiving = true;
waypoint_request_i = 0;
waypoint_request_last = 0;
send_message(MSG_NEXT_WAYPOINT);
send_message(MSG_NEXT_MISSION_REQUEST);
}
break;
}

View File

@ -63,7 +63,7 @@ enum ap_message : uint8_t {
MSG_GPS2_RTK,
MSG_SYSTEM_TIME,
MSG_SERVO_OUT,
MSG_NEXT_WAYPOINT,
MSG_NEXT_MISSION_REQUEST,
MSG_NEXT_PARAM,
MSG_FENCE_STATUS,
MSG_AHRS,

View File

@ -850,11 +850,11 @@ bool GCS_MAVLINK::handle_mission_item(mavlink_message_t *msg, AP_Mission &missio
// only set WP_RADIUS parameter
} else {
waypoint_timelast_request = AP_HAL::millis();
// if we have enough space, then send the next WP immediately
// if we have enough space, then send the next WP request immediately
if (HAVE_PAYLOAD_SPACE(chan, MISSION_ITEM)) {
queued_mission_request_send();
} else {
send_message(MSG_NEXT_WAYPOINT);
send_message(MSG_NEXT_MISSION_REQUEST);
}
}
return mission_is_complete;
@ -874,7 +874,7 @@ mission_ack:
ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) const
{
// MSG_NEXT_WAYPOINT doesn't correspond to a mavlink message directly.
// MSG_NEXT_MISSION_REQUEST doesn't correspond to a mavlink message directly.
// It is used to request the next waypoint after receiving one.
// MSG_NEXT_PARAM doesn't correspond to a mavlink message directly.
@ -1583,7 +1583,7 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us)
gcs().send_text(MAV_SEVERITY_WARNING, "Mission upload timeout");
} else if (tnow - waypoint_timelast_request > wp_recv_time) {
waypoint_timelast_request = tnow;
send_message(MSG_NEXT_WAYPOINT);
send_message(MSG_NEXT_MISSION_REQUEST);
}
}
@ -3614,7 +3614,7 @@ bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
ret = true;
break;
case MSG_NEXT_WAYPOINT:
case MSG_NEXT_MISSION_REQUEST:
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
queued_mission_request_send();
ret = true;
@ -3737,7 +3737,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
case MSG_CURRENT_WAYPOINT:
case MSG_MISSION_ITEM_REACHED:
case MSG_NEXT_WAYPOINT:
case MSG_NEXT_MISSION_REQUEST:
ret = try_send_mission_message(id);
break;