3#include <QtCore/QMetaEnum>
4#include <QtCore/QMetaObject>
18 return QMetaEnum::fromType<SigningFailure::Reason>().valueToKey(
static_cast<int>(r));
24 : QObject(parent), _mavlinkChannel(channel)
26 _timeout.setSingleShot(
true);
27 _timeout.setInterval(kTimeout);
28 connect(&_timeout, &QTimer::timeout,
this, &SigningController::_onTimeout);
29 qCDebug(SigningControllerLog) <<
"SigningController ctor — channel" << _mavlinkChannel;
34 qCDebug(SigningControllerLog) <<
"SigningController dtor — channel" << _mavlinkChannel;
37 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
38 _autoDetectGuard.reset();
39 if (_op.kind == OpKind::Enable) {
46 _channel.
init(_mavlinkChannel, QByteArrayView(),
nullptr);
49void SigningController::_setOpLocked(PendingOp next)
51 _op = std::move(next);
52 QMetaObject::invokeMethod(
this, [
this]() { emit
stateChanged(); }, Qt::AutoConnection);
59 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
64 return State::Enabling;
66 return State::Disabling;
70 return _channel.
isEnabled() ? State::On : State::Off;
90 return (s == State::On) || (s == State::Disabling);
106 if (s == State::Enabling) {
107 return tr(
"Configuring…");
109 if (s == State::Disabling) {
110 return tr(
"Disabling…");
116 const mavlink_signing_status_t lastStatus =
117 (
status &&
status->signing) ?
status->signing->last_status : MAVLINK_SIGNING_STATUS_NONE;
118 switch (lastStatus) {
119 case MAVLINK_SIGNING_STATUS_OK:
120 return QStringLiteral(
"OK");
121 case MAVLINK_SIGNING_STATUS_BAD_SIGNATURE:
122 return QStringLiteral(
"Bad Signature");
123 case MAVLINK_SIGNING_STATUS_NO_STREAMS:
124 return QStringLiteral(
"No Streams");
125 case MAVLINK_SIGNING_STATUS_TOO_MANY_STREAMS:
126 return QStringLiteral(
"Too Many Streams");
127 case MAVLINK_SIGNING_STATUS_OLD_TIMESTAMP:
128 return QStringLiteral(
"Stale Timestamp");
129 case MAVLINK_SIGNING_STATUS_REPLAY:
130 return QStringLiteral(
"Replay Detected");
131 case MAVLINK_SIGNING_STATUS_NONE:
141 if (!snap.keyName.isEmpty() && snap.timestamp > 0) {
145 const bool ok = _channel.
init(_mavlinkChannel, QByteArrayView(),
nullptr);
151 const QString& keyNameHint)
161 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
162 if (_isPendingLocked()) {
163 qCWarning(SigningControllerLog)
164 <<
"[ch" << _mavlinkChannel <<
"] enable rejected: operation already pending";
165 return SigningFailure{FailReason::VehicleUnreachable, tr(
"Signing operation already pending")};
170 const QByteArrayView keyView(
reinterpret_cast<const char*
>(keyBytes.data()), keyBytes.size());
172 if (!_channel.
init(_mavlinkChannel, keyView,
174 persisted, kName,
false)) {
175 qCWarning(SigningControllerLog) <<
"[ch" << _mavlinkChannel <<
"] enable rejected: signing init failed";
176 return SigningFailure{FailReason::InitFailed, tr(
"Failed to install signing for pending verification")};
180 _setOpLocked(PendingOp{
181 .kind = OpKind::Enable,
182 .expectedSysId = expectedSysId,
184 .keyBytes = keyBytes,
189 qCDebug(SigningControllerLog) <<
"[ch" << _mavlinkChannel <<
"] enable pending — key" << kName <<
"sysid"
190 << expectedSysId <<
"timeout" << kTimeout <<
"ms";
197 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
198 if (_isPendingLocked()) {
199 qCWarning(SigningControllerLog)
200 <<
"[ch" << _mavlinkChannel <<
"] disable rejected: operation already pending";
201 return SigningFailure{FailReason::VehicleUnreachable, tr(
"Signing operation already pending")};
206 qCWarning(SigningControllerLog) <<
"[ch" << _mavlinkChannel <<
"] disable rejected: channel not signing";
207 return SigningFailure{FailReason::VehicleUnreachable, tr(
"Channel not signing — cannot disable")};
210 _setOpLocked(PendingOp{
211 .kind = OpKind::Disable,
212 .expectedSysId = expectedSysId,
218 qCDebug(SigningControllerLog) <<
"[ch" << _mavlinkChannel <<
"] disable pending — sysid" << expectedSysId
219 <<
"timeout" << kTimeout <<
"ms";
226 QMetaObject::invokeMethod(
this, [
this]() { emit
stateChanged(); }, Qt::AutoConnection);
231 bool burstFired =
false;
232 uint8_t burstCount = 0;
233 bool pendingEnable =
false;
235 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
236 burstFired = _badSigBurst.
record();
237 burstCount = _badSigBurst.
count();
238 pendingEnable = (_op.kind == OpKind::Enable);
242 const QString detail =
244 ? tr(
"MAVLink signing: %1 consecutive bad signatures while enabling — the chosen key likely "
245 "does not match the vehicle's stored key. Verify the key on the vehicle, then retry.")
247 : tr(
"MAVLink signing: %1 consecutive bad signatures on this link — wrong key or vehicle clock "
250 QMetaObject::invokeMethod(
this, [
this, detail]() { emit
alertRaised(detail); }, Qt::AutoConnection);
256 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
257 _badSigBurst.
reset();
260 bool autoDetected =
false;
265 if (!detected.isEmpty()) {
266 QMetaObject::invokeMethod(
this, [
this, detected]() { emit
keyAutoDetected(detected); }, Qt::AutoConnection);
272 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
273 _handleFsmFrameLocked(message);
281 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
282 _badSigBurst.
reset();
287 if (!_isPendingLocked()) {
290 if (message.sysid != _op.expectedSysId) {
295 if (message.msgid == MAVLINK_MSG_ID_STATUSTEXT) {
296 mavlink_statustext_t st;
297 mavlink_msg_statustext_decode(&message, &st);
298 const QString text = QString::fromLatin1(st.text, qstrnlen(st.text,
sizeof(st.text)));
299 const bool errorSeverity = (st.severity <= MAV_SEVERITY_ERROR);
300 const bool mentionsSigning = text.contains(QLatin1String(
"signing"), Qt::CaseInsensitive);
301 if (errorSeverity && mentionsSigning) {
302 _failLocked(FailReason::InitFailed, tr(
"Vehicle rejected signing change: %1").arg(text));
307 if (_op.kind == OpKind::Enable) {
312 qCWarning(SigningControllerLog)
313 <<
"[ch" << _mavlinkChannel
314 <<
"] pending-enable HEARTBEAT signature did not verify against committed key";
319 }
else if (_op.kind == OpKind::Disable) {
321 _op.unsignedSeen =
true;
327void SigningController::_confirmLocked()
330 QMetaObject::invokeMethod(&_timeout,
"stop", Qt::AutoConnection);
332 if (_op.kind == OpKind::Enable) {
333 const QString confirmedName = _op.keyName;
336 const QString detail = tr(
"Signing confirmation received but local activation failed");
337 qCCritical(SigningControllerLog) <<
"[ch" << _mavlinkChannel <<
"]" << detail;
338 _failLocked(FailReason::InitFailed, detail);
341 qCDebug(SigningControllerLog) <<
"[ch" << _mavlinkChannel <<
"] enable confirmed — key" << confirmedName;
343 QMetaObject::invokeMethod(
344 this, [
this, confirmedName]() { emit
signingConfirmed(confirmedName); }, Qt::AutoConnection);
345 }
else if (_op.kind == OpKind::Disable) {
346 qCDebug(SigningControllerLog) <<
"[ch" << _mavlinkChannel <<
"] disable confirmed";
347 _completeDisableSuccessLocked();
351void SigningController::_completeDisableSuccessLocked()
353 _channel.
init(_mavlinkChannel, QByteArrayView(),
nullptr);
355 QMetaObject::invokeMethod(
this, [
this]() { emit
signingConfirmed(QString{}); }, Qt::AutoConnection);
358void SigningController::_failLocked(FailReason reason,
const QString& detail,
bool cancelled)
360 QMetaObject::invokeMethod(&_timeout,
"stop", Qt::AutoConnection);
363 if (_op.kind == OpKind::Disable && _op.unsignedSeen && !cancelled) {
364 _completeDisableSuccessLocked();
369 QString effectiveDetail = detail;
371 if (_op.kind == OpKind::Enable) {
372 _channel.
init(_mavlinkChannel, QByteArrayView(),
nullptr);
373 }
else if (_op.kind == OpKind::Disable) {
376 effectiveReason = FailReason::VehicleUnreachable;
378 tr(
"Signing disable not confirmed — vehicle is unreachable or still requires signed messages. Local "
379 "signing remains enabled.");
382 qCWarning(SigningControllerLog) <<
"[ch" << _mavlinkChannel
383 <<
"] signing operation failed:" << failReasonName(effectiveReason)
388 QMetaObject::invokeMethod(
this, [
this, failure]() { emit
signingFailed(failure); }, Qt::AutoConnection);
393 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
394 if (!_isPendingLocked()) {
397 const QString effectiveDetail =
399 ? tr(
"Signing operation cancelled — primary link changed before vehicle confirmation")
401 _failLocked(FailReason::VehicleUnreachable, effectiveDetail,
true);
404void SigningController::_onTimeout()
406 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
407 if (!_isPendingLocked()) {
410 qCDebug(SigningControllerLog) <<
"[ch" << _mavlinkChannel <<
"] timeout fired —"
411 << (_op.kind == OpKind::Enable ?
"enable" :
"disable") <<
"not confirmed";
412 const QString detail = (_op.kind == OpKind::Enable) ? tr(
"Signing setup not confirmed by vehicle (timeout)")
413 : tr(
"Signing disable not confirmed by vehicle (timeout)");
414 _failLocked(FailReason::Timeout, detail);
417void SigningController::_clearLocked()
419 _autoDetectGuard.reset();
421 _setOpLocked(PendingOp{});
mavlink_status_t * mavlink_get_channel_status(uint8_t chan)
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static MAVLinkSigningKeys * instance()
void recordTimestamp(const QString &name, uint64_t ts)
Update in-memory + persisted last-timestamp for name. Monotonic — older values are dropped.
QString tryDetectKey(SigningController *controller, const mavlink_message_t &message)
Try every stored key against message's signature; on match, configures channel and returns the key na...
uint64_t lastTimestamp(const QString &name) const
Last persisted signing timestamp for name, or 0 if unknown / no entry.
bool record()
Returns true on the rising-edge crossing into >= threshold.
bool init(mavlink_channel_t channel, QByteArrayView key, mavlink_accept_unsigned_t callback, uint64_t persistedTimestamp=0, const QString &keyName={}, bool signOutgoing=true)
bool setAcceptUnsignedCallback(mavlink_accept_unsigned_t callback)
Swap the accept-unsigned callback without resetting the key. Returns false if signing isn't enabled.
QGC::AutoSuspendGuard suspendAutoDetect()
RAII handle that suspends auto-detect for the guard's lifetime; release is automatic on destruction.
void clearDetectCooldown()
bool consumeStatusTransition(mavlink_channel_t channel)
True if last_status changed since previous call; sole transition-detection source.
TimestampSnapshot currentTimestampAndName() const
Returns current timestamp and active key name. Returns {0, ""} when signing is not enabled.
void signingConfirmed(const QString &keyName)
Emitted exactly once per begin*() on success. keyName is the enabled key, or empty for disable.
SigningController(mavlink_channel_t channel, QObject *parent=nullptr)
std::optional< SigningFailure > tryBeginEnable(uint8_t expectedSysId, const QString &keyName, const MAVLinkSigning::SigningKey &keyBytes)
Begin pending-enable. Caller must send SETUP_SIGNING only on nullopt; outcome arrives via signingConf...
std::optional< SigningFailure > tryBeginDisable(uint8_t expectedSysId)
Atomic check-and-commit for disable; same contract as tryBeginEnable.
bool initSigningImmediate(QByteArrayView key, MAVLinkSigning::UnsignedAcceptancePolicy policy, const QString &keyNameHint={})
Bypasses the FSM; used by tests and auto-detect. Non-empty keyNameHint seeds the persisted timestamp.
bool processFrame(bool framingOk, const mavlink_message_t &message)
Per-frame entry point; drives burst alerts, auto-detect, and the FSM. Returns true on auto-detect.
QString statusText() const
SigningFailure::Reason FailReason
void cancelPending(const QString &detail={})
void alertRaised(const QString &detail)
~SigningController() override
SigningStatus status() const
void keyAutoDetected(const QString &keyName)
void signingFailed(SigningFailure failure)
Emitted exactly once per begin*() on failure (timeout, init error, cancel, re-entry).
Reason a signing operation failed. Used by SigningController error path and Vehicle::signingFailed.
std::array< uint8_t, kSigningKeySize > SigningKey
std::array avoids QByteArray COW detach so secureZero() actually wipes the bytes.
bool verifySignature(QByteArrayView key, const mavlink_message_t &message)
Verify a key against a signed message's signature.
bool isMessageSigned(const mavlink_message_t &message)
Returns true if the message has a MAVLink2 signature.
mavlink_accept_unsigned_t callbackForPolicy(UnsignedAcceptancePolicy policy)
Maps a high-level policy to the underlying libmavlink callback.
void logSigningFailure(mavlink_channel_t channel)
void secureZero(void *data, size_t size)