mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: let GCS superclass specify param float capabilitiy
This commit is contained in:
parent
ba90a1a5df
commit
795afdd259
@ -764,7 +764,6 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg)
|
||||
uint64_t GCS_MAVLINK_Sub::capabilities() const
|
||||
{
|
||||
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
|
||||
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT |
|
||||
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
|
||||
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
|
||||
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
|
||||
|
Loading…
Reference in New Issue
Block a user