From b9dbfff0d0e2fdf9acb8ddec1234d4cd38be6324 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 29 Oct 2019 11:48:52 +1100 Subject: [PATCH] GCS_MAVLink: announce capabilities compass-cal and param float for all vehicles --- libraries/GCS_MAVLink/GCS_Common.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 290940e772..384af57bc1 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4685,7 +4685,8 @@ bool GCS_MAVLINK::mavlink_coordinate_frame_to_location_alt_frame(const MAV_FRAME uint64_t GCS_MAVLINK::capabilities() const { - uint64_t ret = 0; + uint64_t ret = MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | + MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION; AP_SerialManager::SerialProtocol mavlink_protocol = AP::serialmanager().get_mavlink_protocol(chan); if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2) {