Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GCS_MAVLINK: Fix Deprecation of MISSION_REQUEST #28854

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 13 additions & 1 deletion libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7098,8 +7098,20 @@ bool GCS_MAVLINK::mavlink_coordinate_frame_to_location_alt_frame(const MAV_FRAME

uint64_t GCS_MAVLINK::capabilities() const
{
/**
* Basic capabilities, changed December 2024
* - Param float (FIXME: deprecated since 2022)
* - Compass calibration (already there, not checked)
* - Mission Int (added, code is there)
* - Command Int (added, code is there)
* - Set Position Target Global Int (added, code is there, used for guided mode)
* - param encode c cast (TODO: should be added, code is there)
*/
uint64_t ret = MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION;
MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION |
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT;

const auto mavlink_protocol = uartstate->get_protocol();
if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2 || mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLinkHL) {
Expand Down
36 changes: 28 additions & 8 deletions libraries/GCS_MAVLink/MissionItemProtocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@ void MissionItemProtocol::init_send_requests(GCS_MAVLINK &_link,

mission_item_warning_sent = false;
mission_request_warning_sent = false;
mission_request_int_fallback_to_mission_request = false;
mission_request_int_warning_sent = false;
}

void MissionItemProtocol::handle_mission_clear_all(const GCS_MAVLINK &_link,
Expand Down Expand Up @@ -315,7 +317,7 @@ void MissionItemProtocol::handle_mission_item(const mavlink_message_t &msg, cons
return;
}
// if we have enough space, then send the next WP request immediately
if (HAVE_PAYLOAD_SPACE(link->get_chan(), MISSION_REQUEST)) {
if (mission_request_int_fallback_to_mission_request ? HAVE_PAYLOAD_SPACE(link->get_chan(), MISSION_REQUEST) : HAVE_PAYLOAD_SPACE(link->get_chan(), MISSION_REQUEST_INT)) {
queued_request_send();
} else {
link->send_message(next_item_ap_message_id());
Expand Down Expand Up @@ -368,13 +370,24 @@ void MissionItemProtocol::queued_request_send()
INTERNAL_ERROR(AP_InternalError::error_t::gcs_bad_missionprotocol_link);
return;
}
CHECK_PAYLOAD_SIZE2_VOID(link->get_chan(), MISSION_REQUEST);
mavlink_msg_mission_request_send(
link->get_chan(),
dest_sysid,
dest_compid,
request_i,
mission_type());
if (mission_request_int_fallback_to_mission_request) {
CHECK_PAYLOAD_SIZE2_VOID(link->get_chan(), MISSION_REQUEST);
mavlink_msg_mission_request_int_send(
link->get_chan(),
dest_sysid,
dest_compid,
request_i,
mission_type());
} else {
CHECK_PAYLOAD_SIZE2_VOID(link->get_chan(), MISSION_REQUEST_INT);
mavlink_msg_mission_request_send(
link->get_chan(),
dest_sysid,
dest_compid,
request_i,
mission_type());
}

timelast_request_ms = AP_HAL::millis();
}

Expand Down Expand Up @@ -408,8 +421,15 @@ void MissionItemProtocol::update()
// resend request if we haven't gotten one:
const uint32_t wp_recv_timeout_ms = 1000U + link->get_stream_slowdown_ms();
if (tnow - timelast_request_ms > wp_recv_timeout_ms) {
if (not mission_request_int_fallback_to_mission_request) {
mission_request_int_fallback_to_mission_request = true;
}
timelast_request_ms = tnow;
link->send_message(next_item_ap_message_id());
} else if ((mission_request_int_fallback_to_mission_request)
&& (not mission_request_int_warning_sent)) {
mission_request_int_warning_sent = true;
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "This GCS ignores MISSION_REQUEST_INT; MISSION_REQUEST support will soon end!");
}
}

Expand Down
6 changes: 6 additions & 0 deletions libraries/GCS_MAVLink/MissionItemProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,12 @@ class MissionItemProtocol
// then we issue a warning - once per transfer.
bool mission_item_warning_sent = false;

// if the autopilot sends a mission_request_int to a GCS and runs into a timeout,
// it does fallback to mission_request instead, ...
bool mission_request_int_fallback_to_mission_request = false;
// ... and we issue a warning - once per transfer.
bool mission_request_int_warning_sent = false;

// support for GCS getting waypoints etc from us:
virtual MAV_MISSION_RESULT get_item(const GCS_MAVLINK &_link,
const mavlink_message_t &msg,
Expand Down
Loading