diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0 index 6bbc8a51d8f37537732d3f5170093d49e64c6f4b..5be9f5bf6002d58199cafafb5d416929fb8d8bcd 160000 --- a/libs/mavlink/include/mavlink/v2.0 +++ b/libs/mavlink/include/mavlink/v2.0 @@ -1 +1 @@ -Subproject commit 6bbc8a51d8f37537732d3f5170093d49e64c6f4b +Subproject commit 5be9f5bf6002d58199cafafb5d416929fb8d8bcd diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index adcc5d0c1b37a2921e4ddb6ae0bdfc8c49d8a00a..09a50bd4d98f3439b68f1f1bf166987b49f8f20a 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -588,7 +588,10 @@ void APMSensorsComponentController::nextClicked(void) &msg, 0, // command 1, // result - 0); // progress + 0, // progress + 0, // result_param2 + 0, // target_system + 0); // target_component _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc index 4a7fba0cee673f27f25f7231647f4488de7741f7..7d9b848ef3280c39da4beb3077c30b0b55f2db08 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -18,6 +18,8 @@ #include #include +static const char* kInvalidConverstion = "Internal Error: No support for string parameters"; + QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog") QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVerboseLog") @@ -57,13 +59,17 @@ QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string, convertTo = QVariant::Double; break; case FactMetaData::valueTypeString: - qWarning() << "Internal Error: No support for string parameters"; + qWarning() << kInvalidConverstion; convertTo = QVariant::String; break; case FactMetaData::valueTypeBool: - qWarning() << "Internal Error: No support for string parameters"; + qWarning() << kInvalidConverstion; convertTo = QVariant::Bool; break; + case FactMetaData::valueTypeCustom: + qWarning() << kInvalidConverstion; + convertTo = QVariant::ByteArray; + break; } *convertOk = var.convert(convertTo); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 5d2c69ab7f1d69b9374177caedf855c71cd6a98d..9fc162a5700cac193755c47d35533ad87633a830 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -692,8 +692,6 @@ public: uint64_t capabilityBits (void) const { return _capabilityBits; } // Change signalled by capabilityBitsChanged QGCCameraManager* dynamicCameras () { return _cameras; } - bool capabilitiesKnown(void) const { return _vehicleCapabilitiesKnown; } - /// @true: When flying a mission the vehicle is always facing towards the next waypoint bool vehicleYawsToNextWaypointInMission(void) const; diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index 70a1fc5210cdbc064c9ef3114fb853c0dc5c2ae9..c9872fef87e8c3693fd4202c3bfe97c81da61c9e 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -870,7 +870,10 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg) &commandAck, request.command, commandResult, - 0); + 0, // progress + 0, // result_param2 + 0, // target_system + 0); // target_component respondWithMavlinkMessage(commandAck); }