From 976acb3a58158ca7b2c0fe2f34b95e2215aab787 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 29 Oct 2019 11:47:35 +1100 Subject: [PATCH] Copter: let GCS superclass specify compass and param float capabilitiy --- ArduCopter/GCS_Mavlink.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 32505524b1..4ecf2b0e46 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1321,7 +1321,6 @@ float GCS_MAVLINK_Copter::vfr_hud_alt() const uint64_t GCS_MAVLINK_Copter::capabilities() const { return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT | - MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MISSION_INT | MAV_PROTOCOL_CAPABILITY_COMMAND_INT | MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED | @@ -1331,7 +1330,6 @@ uint64_t GCS_MAVLINK_Copter::capabilities() const #if AP_TERRAIN_AVAILABLE && AC_TERRAIN (copter.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) | #endif - MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION | GCS_MAVLINK::capabilities()); }