mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
GCS_MAVLink: rename queued_waypoint_send to queued_mission_request_send
This commit is contained in:
parent
81f77f5311
commit
da1ded7cb9
@ -124,7 +124,7 @@ public:
|
|||||||
void send_text(MAV_SEVERITY severity, const char *fmt, ...);
|
void send_text(MAV_SEVERITY severity, const char *fmt, ...);
|
||||||
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list);
|
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list);
|
||||||
void queued_param_send();
|
void queued_param_send();
|
||||||
void queued_waypoint_send();
|
void queued_mission_request_send();
|
||||||
// packetReceived is called on any successful decode of a mavlink message
|
// packetReceived is called on any successful decode of a mavlink message
|
||||||
virtual void packetReceived(const mavlink_status_t &status,
|
virtual void packetReceived(const mavlink_status_t &status,
|
||||||
mavlink_message_t &msg);
|
mavlink_message_t &msg);
|
||||||
|
@ -174,7 +174,7 @@ GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager
|
|||||||
* handling code
|
* handling code
|
||||||
*/
|
*/
|
||||||
void
|
void
|
||||||
GCS_MAVLINK::queued_waypoint_send()
|
GCS_MAVLINK::queued_mission_request_send()
|
||||||
{
|
{
|
||||||
if (initialised &&
|
if (initialised &&
|
||||||
waypoint_receiving &&
|
waypoint_receiving &&
|
||||||
@ -852,7 +852,7 @@ bool GCS_MAVLINK::handle_mission_item(mavlink_message_t *msg, AP_Mission &missio
|
|||||||
waypoint_timelast_request = AP_HAL::millis();
|
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 immediately
|
||||||
if (HAVE_PAYLOAD_SPACE(chan, MISSION_ITEM)) {
|
if (HAVE_PAYLOAD_SPACE(chan, MISSION_ITEM)) {
|
||||||
queued_waypoint_send();
|
queued_mission_request_send();
|
||||||
} else {
|
} else {
|
||||||
send_message(MSG_NEXT_WAYPOINT);
|
send_message(MSG_NEXT_WAYPOINT);
|
||||||
}
|
}
|
||||||
@ -3616,7 +3616,7 @@ bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
|
|||||||
break;
|
break;
|
||||||
case MSG_NEXT_WAYPOINT:
|
case MSG_NEXT_WAYPOINT:
|
||||||
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
|
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
|
||||||
queued_waypoint_send();
|
queued_mission_request_send();
|
||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
Loading…
Reference in New Issue
Block a user