GCS_MAVLink: queue AUTOPILOT_VERSION for sending instead of direct-send

Also allows the message to be requested for streaming or with
REQUEST_MESSAGE

We weren't checking for buffer space before sending this out, so it was
a possible source of corruption.
This commit is contained in:
Peter Barker 2019-08-13 14:23:42 +10:00 committed by Peter Barker
parent 5e40921b42
commit bb542ca39a
2 changed files with 9 additions and 2 deletions

View File

@ -797,6 +797,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_AOA_SSA, MSG_AOA_SSA},
{ MAVLINK_MSG_ID_DEEPSTALL, MSG_LANDING},
{ MAVLINK_MSG_ID_EXTENDED_SYS_STATE, MSG_EXTENDED_SYS_STATE},
{ MAVLINK_MSG_ID_AUTOPILOT_VERSION, MSG_AUTOPILOT_VERSION},
};
for (uint8_t i=0; i<ARRAY_SIZE(map); i++) {
@ -3143,7 +3144,7 @@ void GCS_MAVLINK::handle_common_mission_message(const mavlink_message_t &msg)
void GCS_MAVLINK::handle_send_autopilot_version(const mavlink_message_t &msg)
{
send_autopilot_version();
send_message(MSG_AUTOPILOT_VERSION);
}
void GCS_MAVLINK::send_banner()
@ -3362,7 +3363,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavl
return MAV_RESULT_FAILED;
}
send_autopilot_version();
send_message(MSG_AUTOPILOT_VERSION);
return MAV_RESULT_ACCEPTED;
}
@ -4251,6 +4252,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_vibration();
break;
case MSG_AUTOPILOT_VERSION:
CHECK_PAYLOAD_SIZE(AUTOPILOT_VERSION);
send_autopilot_version();
break;
case MSG_ESC_TELEMETRY: {
#ifdef HAVE_AP_BLHELI_SUPPORT
CHECK_PAYLOAD_SIZE(ESC_TELEMETRY_1_TO_4);

View File

@ -71,5 +71,6 @@ enum ap_message : uint8_t {
MSG_HOME,
MSG_NAMED_FLOAT,
MSG_EXTENDED_SYS_STATE,
MSG_AUTOPILOT_VERSION,
MSG_LAST // MSG_LAST must be the last entry in this enum
};