mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Rover: let GCS superclass specify compass and param float capabilitiy
This commit is contained in:
parent
23ee9eef5f
commit
d664f18ce4
@ -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());
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user