Rover: let GCS superclass specify compass and param float capabilitiy

This commit is contained in:
Peter Barker 2019-10-29 11:46:51 +11:00 committed by Andrew Tridgell
parent 23ee9eef5f
commit d664f18ce4

View File

@ -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());
}