Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 17 additions & 0 deletions src/Comms/LinkInterface.cc
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ bool LinkInterface::_allocateMavlinkChannel()

qCDebug(LinkInterfaceLog) << "_allocateMavlinkChannel" << _mavlinkChannel;

mavlink_set_proto_version(_mavlinkChannel, MAVLINK_VERSION); // We only support v2 protcol
Copy link

Copilot AI Nov 25, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Typo in comment: "protcol" should be "protocol".

Suggested change
mavlink_set_proto_version(_mavlinkChannel, MAVLINK_VERSION); // We only support v2 protcol
mavlink_set_proto_version(_mavlinkChannel, MAVLINK_VERSION); // We only support v2 protocol

Copilot uses AI. Check for mistakes.
initMavlinkSigning();

return true;
Expand Down Expand Up @@ -140,3 +141,19 @@ void LinkInterface::setSigningSignatureFailure(bool failure)
}
}
}

void LinkInterface::reportMavlinkV1Traffic()
{
if (!_mavlinkV1TrafficReported) {
_mavlinkV1TrafficReported = true;

const SharedLinkConfigurationPtr linkConfig = linkConfiguration();
const QString linkName = linkConfig ? linkConfig->name() : QStringLiteral("unknown");
qCWarning(LinkInterfaceLog) << "MAVLink v1 traffic detected on link" << linkName;
const QString message = tr("MAVLink v1 traffic detected on link '%1'. "
"%2 only supports MAVLink v2. "
"Please ensure your vehicle is configured to use MAVLink v2.")
.arg(linkName).arg(qgcApp()->applicationName());
qgcApp()->showAppMessage(message);
}
}
2 changes: 2 additions & 0 deletions src/Comms/LinkInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ class LinkInterface : public QObject
void removeVehicleReference();
bool initMavlinkSigning();
void setSigningSignatureFailure(bool failure);
void reportMavlinkV1Traffic();

signals:
void bytesReceived(LinkInterface *link, const QByteArray &data);
Expand Down Expand Up @@ -80,6 +81,7 @@ private slots:
bool _decodedFirstMavlinkPacket = false;
int _vehicleReferenceCount = 0;
bool _signingSignatureFailure = false;
bool _mavlinkV1TrafficReported = false;
};

typedef std::shared_ptr<LinkInterface> SharedLinkInterfacePtr;
Expand Down
1 change: 0 additions & 1 deletion src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,6 @@ bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr &config)
(void) connect(link.get(), &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);

MAVLinkProtocol::instance()->resetMetadataForLink(link.get());
MAVLinkProtocol::instance()->setVersion(MAVLinkProtocol::instance()->getCurrentVersion());

// Try to connect before adding to active links list
if (!link->_connect()) {
Expand Down
36 changes: 6 additions & 30 deletions src/Comms/MAVLinkProtocol.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <QtCore/QMetaType>
#include <QtCore/QSettings>
#include <QtCore/QStandardPaths>
#include <QtCore/QTimer>

QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "Comms.MAVLinkProtocol")

Expand Down Expand Up @@ -59,16 +60,6 @@ void MAVLinkProtocol::init()
_initialized = true;
}

void MAVLinkProtocol::setVersion(unsigned version)
{
const QList<SharedLinkInterfacePtr> sharedLinks = LinkManager::instance()->links();
for (const SharedLinkInterfacePtr &interface : sharedLinks) {
mavlink_set_proto_version(interface.get()->mavlinkChannel(), version / 100);
}

_currentVersion = version;
}

void MAVLinkProtocol::resetMetadataForLink(LinkInterface *link)
{
const uint8_t channel = link->mavlinkChannel();
Expand Down Expand Up @@ -119,7 +110,11 @@ void MAVLinkProtocol::receiveBytes(LinkInterface *link, const QByteArray &data)
continue;
}

_updateVersion(link, mavlinkChannel);
if (status.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
link->reportMavlinkV1Traffic();
continue;
}

_updateCounters(mavlinkChannel, message);
if (!linkPtr->linkConfiguration()->isForwarding()) {
_forward(message);
Expand All @@ -133,25 +128,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface *link, const QByteArray &data)
}
}

void MAVLinkProtocol::_updateVersion(LinkInterface *link, uint8_t mavlinkChannel)
{
if (link->decodedFirstMavlinkPacket()) {
return;
}

link->setDecodedFirstMavlinkPacket(true);
const mavlink_status_t *const mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);

if (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
return;
}

if (mavlink_get_proto_version(mavlinkChannel) == 1) {
qCDebug(MAVLinkProtocolLog) << "Switching outbound to mavlink 2.0 due to incoming mavlink 2.0 packet:" << mavlinkChannel;
setVersion(200);
}
}

void MAVLinkProtocol::_updateCounters(uint8_t mavlinkChannel, const mavlink_message_t &message)
{
_totalReceiveCounter[mavlinkChannel]++;
Expand Down
11 changes: 0 additions & 11 deletions src/Comms/MAVLinkProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,21 +51,12 @@ class MAVLinkProtocol : public QObject
/// Get the component id of this application
static int getComponentId() { return MAV_COMP_ID_MISSIONPLANNER; }

/// Get the protocol version
static int getVersion() { return MAVLINK_VERSION; }

/// Get the currently configured protocol version
unsigned getCurrentVersion() const { return _currentVersion; }

/// Reset the counters for all metadata for this link.
void resetMetadataForLink(LinkInterface *link);

/// Suspend/Restart logging during replay.
void suspendLogForReplay(bool suspend) { _logSuspendReplay = suspend; }

/// Set protocol version
void setVersion(unsigned version);

/// Checks the temp directory for log files which may have been left there.
/// This could happen if QGC crashes without the temp log file being saved.
/// Give the user an option to save these orphaned files.
Expand Down Expand Up @@ -107,7 +98,6 @@ private slots:

void _updateCounters(uint8_t mavlinkChannel, const mavlink_message_t &message);
bool _updateStatus(LinkInterface *link, const SharedLinkInterfacePtr linkPtr, uint8_t mavlinkChannel, const mavlink_message_t &message);
void _updateVersion(LinkInterface *link, uint8_t mavlinkChannel);

void _saveTelemetryLog(const QString &tempLogfile);
bool _checkTelemetrySavePath();
Expand All @@ -124,7 +114,6 @@ private slots:
uint64_t _totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]{}; ///< Total messages lost during transmission.
float _runningLossPercent[MAVLINK_COMM_NUM_BUFFERS]{}; ///< Loss rate

unsigned _currentVersion = 100;
bool _initialized = false;

static constexpr const char *_tempLogFileTemplate = "FlightDataXXXXXX"; ///< Template for temporary log file
Expand Down
2 changes: 0 additions & 2 deletions src/Comms/MockLink/MockConfiguration.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,6 @@ class MockConfiguration : public LinkConfiguration
FailMissingParamOnAllRequests, // Not all params are sent on initial request, QGC retries will fail as well
FailInitialConnectRequestMessageAutopilotVersionFailure, // REQUEST_MESSAGE:AUTOPILOT_VERSION returns failure
FailInitialConnectRequestMessageAutopilotVersionLost, // REQUEST_MESSAGE:AUTOPILOT_VERSION success, AUTOPILOT_VERSION never sent
FailInitialConnectRequestMessageProtocolVersionFailure, // REQUEST_MESSAGE:PROTOCOL_VERSION returns failure
FailInitialConnectRequestMessageProtocolVersionLost, // REQUEST_MESSAGE:PROTOCOL_VERSION success, PROTOCOL_VERSION never sent
};
FailureMode_t failureMode() const { return _failureMode; }
void setFailureMode(FailureMode_t failureMode) { _failureMode = failureMode; }
Expand Down
36 changes: 0 additions & 36 deletions src/Comms/MockLink/MockLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1818,39 +1818,6 @@ void MockLink::_handleRequestMessageAutopilotVersion(const mavlink_command_long_
_respondWithAutopilotVersion();
}

void MockLink::_handleRequestMessageProtocolVersion(const mavlink_command_long_t &request, bool &accepted)
{
accepted = true;

switch (_failureMode) {
case MockConfiguration::FailNone:
break;
case MockConfiguration::FailInitialConnectRequestMessageProtocolVersionFailure:
accepted = false;
return;
case MockConfiguration::FailInitialConnectRequestMessageProtocolVersionLost:
accepted = true;
return;
default:
break;
}

const uint8_t nullHash[8]{};
mavlink_message_t responseMsg{};
(void) mavlink_msg_protocol_version_pack_chan(
_vehicleSystemId,
_vehicleComponentId,
mavlinkChannel(),
&responseMsg,
200,
100,
200,
nullHash,
nullHash
);
respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleRequestMessageDebug(const mavlink_command_long_t &request, bool &accepted, bool &noAck)
{
accepted = true;
Expand Down Expand Up @@ -1946,9 +1913,6 @@ void MockLink::_handleRequestMessage(const mavlink_command_long_t &request, bool
case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
_handleRequestMessageAutopilotVersion(request, accepted);
break;
case MAVLINK_MSG_ID_PROTOCOL_VERSION:
_handleRequestMessageProtocolVersion(request, accepted);
break;
case MAVLINK_MSG_ID_COMPONENT_METADATA:
if (_firmwareType == MAV_AUTOPILOT_PX4) {
_sendGeneralMetaData();
Expand Down
1 change: 0 additions & 1 deletion src/Comms/MockLink/MockLink.h
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,6 @@ private slots:
void _handleParamMapRC(const mavlink_message_t &msg);
void _handleRequestMessage(const mavlink_command_long_t &request, bool &accepted, bool &noAck);
void _handleRequestMessageAutopilotVersion(const mavlink_command_long_t &request, bool &accepted);
void _handleRequestMessageProtocolVersion(const mavlink_command_long_t &request, bool &accepted);
void _handleRequestMessageDebug(const mavlink_command_long_t &request, bool &accepted, bool &noAck);
void _handleRequestMessageAvailableModes(const mavlink_command_long_t &request, bool &accepted);
void _handleRequestMessageGimbalManagerInformation(const mavlink_command_long_t &request, bool &accepted);
Expand Down
8 changes: 1 addition & 7 deletions src/MissionManager/GeoFenceController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -105,17 +105,11 @@ void GeoFenceController::_managerVehicleChanged(Vehicle* managerVehicle)
connect(_geoFenceManager, &GeoFenceManager::removeAllComplete, this, &GeoFenceController::_managerRemoveAllComplete);
connect(_geoFenceManager, &GeoFenceManager::inProgressChanged, this, &GeoFenceController::syncInProgressChanged);

//-- GeoFenceController::supported() tests both the capability bit AND the protocol version.
(void) connect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, [this](uint64_t capabilityBits) {
Q_UNUSED(capabilityBits);
emit supportedChanged(supported());
});

(void) connect(_managerVehicle, &Vehicle::requestProtocolVersion, this, [this](unsigned version) {
Q_UNUSED(version);
emit supportedChanged(supported());
});

connect(_managerVehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &GeoFenceController::_parametersReady);
_parametersReady();

Expand Down Expand Up @@ -489,7 +483,7 @@ void GeoFenceController::clearAllInteractive(void)

bool GeoFenceController::supported(void) const
{
return (_managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE) && (_managerVehicle->maxProtoVersion() >= 200);
return _managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE;
}

/* Returns the radius of the "paramCircularFence"
Expand Down
2 changes: 1 addition & 1 deletion src/MissionManager/GeoFenceManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -193,5 +193,5 @@ void GeoFenceManager::_planManagerLoadComplete(bool removeAllRequested)

bool GeoFenceManager::supported(void) const
{
return (_vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE) && (_vehicle->maxProtoVersion() >= 200);
return _vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE;
}
1 change: 0 additions & 1 deletion src/MissionManager/MavCmdInfoCommon.json
Original file line number Diff line number Diff line change
Expand Up @@ -1145,7 +1145,6 @@
{ "id": 510, "rawName": "MAV_CMD_GET_MESSAGE_INTERVAL", "friendlyName": "Get message interval" },
{ "id": 511, "rawName": "MAV_CMD_SET_MESSAGE_INTERVAL", "friendlyName": "Set message interval" },
{ "id": 512, "rawName": "MAV_CMD_REQUEST_MESSAGE" },
{ "id": 519, "rawName": "MAV_CMD_REQUEST_PROTOCOL_VERSION" },
{ "id": 520, "rawName": "MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES", "friendlyName": "Get capabilities" },
{
"id": 530,
Expand Down
8 changes: 1 addition & 7 deletions src/MissionManager/RallyPointController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -66,17 +66,11 @@ void RallyPointController::_managerVehicleChanged(Vehicle* managerVehicle)
connect(_rallyPointManager, &RallyPointManager::removeAllComplete, this, &RallyPointController::_managerRemoveAllComplete);
connect(_rallyPointManager, &RallyPointManager::inProgressChanged, this, &RallyPointController::syncInProgressChanged);

//-- RallyPointController::supported() tests both the capability bit AND the protocol version.
(void) connect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, [this](uint64_t capabilityBits) {
Q_UNUSED(capabilityBits);
emit supportedChanged(supported());
});

(void) connect(_managerVehicle, &Vehicle::requestProtocolVersion, this, [this](unsigned version) {
Q_UNUSED(version);
emit supportedChanged(supported());
});

emit supportedChanged(supported());
}

Expand Down Expand Up @@ -261,7 +255,7 @@ void RallyPointController::addPoint(QGeoCoordinate point)

bool RallyPointController::supported(void) const
{
return (_managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY) && (_managerVehicle->maxProtoVersion() >= 200);
return _managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY;
}

void RallyPointController::removePoint(QObject* rallyPoint)
Expand Down
2 changes: 1 addition & 1 deletion src/MissionManager/RallyPointManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ void RallyPointManager::removeAll(void)

bool RallyPointManager::supported(void) const
{
return (_vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY) && (_vehicle->maxProtoVersion() >= 200);
return _vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY;
}

void RallyPointManager::_planManagerLoadComplete(bool removeAllRequested)
Expand Down
1 change: 0 additions & 1 deletion src/Settings/MavlinkSettings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@ DECLARE_SETTINGSFACT(MavlinkSettings, forwardMavlinkHostName)
DECLARE_SETTINGSFACT(MavlinkSettings, forwardMavlinkAPMSupportHostName)
DECLARE_SETTINGSFACT(MavlinkSettings, sendGCSHeartbeat)
DECLARE_SETTINGSFACT(MavlinkSettings, gcsMavlinkSystemID)
DECLARE_SETTINGSFACT(MavlinkSettings, requireMatchingMavlinkVersions)

DECLARE_SETTINGSFACT_NO_FUNC(MavlinkSettings, mavlink2SigningKey)
{
Expand Down
1 change: 0 additions & 1 deletion src/Settings/MavlinkSettings.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@ class MavlinkSettings : public SettingsGroup
DEFINE_SETTINGFACT(mavlink2SigningKey)
DEFINE_SETTINGFACT(sendGCSHeartbeat)
DEFINE_SETTINGFACT(gcsMavlinkSystemID)
DEFINE_SETTINGFACT(requireMatchingMavlinkVersions)

// Although this is a global setting it only affects ArduPilot vehicle since PX4 automatically starts the stream from the vehicle side
DEFINE_SETTINGFACT(apmStartMavlinkStreams)
Expand Down
Loading
Loading