From d664f18ce451922b19b991fd9c7bd16021b864ad Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 29 Oct 2019 11:46:51 +1100 Subject: [PATCH] Rover: let GCS superclass specify compass and param float capabilitiy --- APMrover2/GCS_Mavlink.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 2e66290c0c..dd6dfca0bc 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1050,13 +1050,11 @@ void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg) uint64_t GCS_MAVLINK_Rover::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 | MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT | MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET | - MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION | GCS_MAVLINK::capabilities()); }