diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 9809935c1b..9aa183ce68 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1389,7 +1389,6 @@ void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, const ma uint64_t GCS_MAVLINK_Plane::capabilities() const { return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT | - MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_COMMAND_INT | MAV_PROTOCOL_CAPABILITY_MISSION_INT | MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT | @@ -1397,6 +1396,5 @@ uint64_t GCS_MAVLINK_Plane::capabilities() const #if AP_TERRAIN_AVAILABLE (plane.terrain.enabled() ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0) | #endif - MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION | GCS_MAVLINK::capabilities()); }