QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
SigningController.cc
Go to the documentation of this file.
1#include "SigningController.h"
2
3#include <QtCore/QMetaEnum>
4#include <QtCore/QMetaObject>
5
6#include "MAVLinkLib.h"
7#include "MAVLinkSigning.h"
10#include "SecureMemory.h"
11
12QGC_LOGGING_CATEGORY(SigningControllerLog, "MAVLink.SigningController")
13
14namespace {
15
16const char* failReasonName(SigningController::FailReason r)
17{
18 return QMetaEnum::fromType<SigningFailure::Reason>().valueToKey(static_cast<int>(r));
19}
20
21} // namespace
22
24 : QObject(parent), _mavlinkChannel(channel)
25{
26 _timeout.setSingleShot(true);
27 _timeout.setInterval(kTimeout);
28 connect(&_timeout, &QTimer::timeout, this, &SigningController::_onTimeout);
29 qCDebug(SigningControllerLog) << "SigningController ctor — channel" << _mavlinkChannel;
30}
31
33{
34 qCDebug(SigningControllerLog) << "SigningController dtor — channel" << _mavlinkChannel;
35 _timeout.stop();
36 {
37 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
38 _autoDetectGuard.reset();
39 if (_op.kind == OpKind::Enable) {
40 QGC::secureZero(_op.keyBytes);
41 }
42 _op = PendingOp{};
43 }
44
45 // Detach status->signing before _channel dies — otherwise the next parser call dangles.
46 _channel.init(_mavlinkChannel, QByteArrayView(), nullptr);
47}
48
49void SigningController::_setOpLocked(PendingOp next)
50{
51 _op = std::move(next);
52 QMetaObject::invokeMethod(this, [this]() { emit stateChanged(); }, Qt::AutoConnection);
53}
54
56{
57 OpKind kind;
58 {
59 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
60 kind = _op.kind;
61 }
62 switch (kind) {
63 case OpKind::Enable:
64 return State::Enabling;
65 case OpKind::Disable:
66 return State::Disabling;
67 case OpKind::None:
68 break;
69 }
70 return _channel.isEnabled() ? State::On : State::Off;
71}
72
74{
76 s.state = state();
77 // Enabling installs the channel struct but isn't surfaced as enabled; Disabling stays enabled until vehicle
78 // confirms.
79 s.enabled = (s.state == State::On) || (s.state == State::Disabling);
80 s.keyName = _channel.keyHint();
82 s.streamCount = _channel.streamCount();
83 return s;
84}
85
87{
88 // Excludes Enabling: channel struct installed for verify but vehicle hasn't confirmed yet.
89 const State s = state();
90 return (s == State::On) || (s == State::Disabling);
91}
92
94{
95 return _channel.keyHint();
96}
97
99{
100 return _channel.streamCount();
101}
102
104{
105 const State s = state();
106 if (s == State::Enabling) {
107 return tr("Configuring…");
108 }
109 if (s == State::Disabling) {
110 return tr("Disabling…");
111 }
112 if (!_channel.isEnabled()) {
113 return tr("Off");
114 }
115 const mavlink_status_t* const status = mavlink_get_channel_status(_mavlinkChannel);
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:
132 default:
133 return tr("On");
134 }
135}
136
138{
139 if (_channel.isEnabled()) {
140 const auto snap = _channel.currentTimestampAndName();
141 if (!snap.keyName.isEmpty() && snap.timestamp > 0) {
142 MAVLinkSigningKeys::instance()->recordTimestamp(snap.keyName, snap.timestamp);
143 }
144 }
145 const bool ok = _channel.init(_mavlinkChannel, QByteArrayView(), nullptr);
146 _channel.clearDetectCooldown();
147 return ok;
148}
149
151 const QString& keyNameHint)
152{
153 const uint64_t persisted = keyNameHint.isEmpty() ? 0 : MAVLinkSigningKeys::instance()->lastTimestamp(keyNameHint);
154 return _channel.init(_mavlinkChannel, key, MAVLinkSigning::callbackForPolicy(policy), persisted, keyNameHint);
155}
156
157std::optional<SigningFailure> SigningController::tryBeginEnable(uint8_t expectedSysId, const QString& kName,
158 const MAVLinkSigning::SigningKey& keyBytes)
159{
160 {
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")};
166 }
167
168 // PendingEnableVerifyOnly: signOutgoing=false, lenient policy keeps non-responding vehicle observable while lib
169 // verifies its signed reply.
170 const QByteArrayView keyView(reinterpret_cast<const char*>(keyBytes.data()), keyBytes.size());
171 const uint64_t persisted = kName.isEmpty() ? 0 : MAVLinkSigningKeys::instance()->lastTimestamp(kName);
172 if (!_channel.init(_mavlinkChannel, keyView,
174 persisted, kName, /*signOutgoing=*/false)) {
175 qCWarning(SigningControllerLog) << "[ch" << _mavlinkChannel << "] enable rejected: signing init failed";
176 return SigningFailure{FailReason::InitFailed, tr("Failed to install signing for pending verification")};
177 }
178
179 _autoDetectGuard.emplace(_channel.suspendAutoDetect());
180 _setOpLocked(PendingOp{
181 .kind = OpKind::Enable,
182 .expectedSysId = expectedSysId,
183 .keyName = kName,
184 .keyBytes = keyBytes,
185 });
186 }
187 // QTimer is owned by main thread; tryBeginEnable is called on the main thread.
188 _timeout.start();
189 qCDebug(SigningControllerLog) << "[ch" << _mavlinkChannel << "] enable pending — key" << kName << "sysid"
190 << expectedSysId << "timeout" << kTimeout << "ms";
191 return std::nullopt;
192}
193
194std::optional<SigningFailure> SigningController::tryBeginDisable(uint8_t expectedSysId)
195{
196 {
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")};
202 }
203
204 if (!_channel.setAcceptUnsignedCallback(
206 qCWarning(SigningControllerLog) << "[ch" << _mavlinkChannel << "] disable rejected: channel not signing";
207 return SigningFailure{FailReason::VehicleUnreachable, tr("Channel not signing — cannot disable")};
208 }
209
210 _setOpLocked(PendingOp{
211 .kind = OpKind::Disable,
212 .expectedSysId = expectedSysId,
213 .keyName = {},
214 .keyBytes = {},
215 });
216 }
217 _timeout.start();
218 qCDebug(SigningControllerLog) << "[ch" << _mavlinkChannel << "] disable pending — sysid" << expectedSysId
219 << "timeout" << kTimeout << "ms";
220 return std::nullopt;
221}
222
223bool SigningController::processFrame(bool framingOk, const mavlink_message_t& message)
224{
225 if (_channel.consumeStatusTransition(_mavlinkChannel)) {
226 QMetaObject::invokeMethod(this, [this]() { emit stateChanged(); }, Qt::AutoConnection);
227 }
228
229 if (!framingOk) {
230 MAVLinkSigning::logSigningFailure(_mavlinkChannel);
231 bool burstFired = false;
232 uint8_t burstCount = 0;
233 bool pendingEnable = false;
234 {
235 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
236 burstFired = _badSigBurst.record();
237 burstCount = _badSigBurst.count();
238 pendingEnable = (_op.kind == OpKind::Enable);
239 }
240 if (burstFired) {
241 // Pending-enable burst: user is staring at "Configuring…"; tell them it's a key mismatch.
242 const QString detail =
243 pendingEnable
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.")
246 .arg(burstCount)
247 : tr("MAVLink signing: %1 consecutive bad signatures on this link — wrong key or vehicle clock "
248 "drift")
249 .arg(burstCount);
250 QMetaObject::invokeMethod(this, [this, detail]() { emit alertRaised(detail); }, Qt::AutoConnection);
251 }
252 return false;
253 }
254
255 {
256 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
257 _badSigBurst.reset();
258 }
259
260 bool autoDetected = false;
261 if (MAVLinkSigning::isMessageSigned(message) && !_channel.isEnabled()) {
262 // Auto-detect bypasses the deferred-confirm FSM intentionally: tryDetectKey verifies the HMAC first, so the
263 // vehicle is provably already signing with this key.
264 const QString detected = MAVLinkSigningKeys::instance()->tryDetectKey(this, message);
265 if (!detected.isEmpty()) {
266 QMetaObject::invokeMethod(this, [this, detected]() { emit keyAutoDetected(detected); }, Qt::AutoConnection);
267 autoDetected = true;
268 }
269 }
270
271 {
272 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
273 _handleFsmFrameLocked(message);
274 }
275
276 return autoDetected;
277}
278
280{
281 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
282 _badSigBurst.reset();
283}
284
285void SigningController::_handleFsmFrameLocked(const mavlink_message_t& message)
286{
287 if (!_isPendingLocked()) {
288 return;
289 }
290 if (message.sysid != _op.expectedSysId) {
291 return;
292 }
293
294 // ERROR-severity STATUSTEXT mentioning "signing" → fast-fail (e.g. ArduPilot armed-rejection) before 5s timeout.
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));
303 return;
304 }
305 }
306
307 if (_op.kind == OpKind::Enable) {
308 if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT && MAVLinkSigning::isMessageSigned(message)) {
309 // Defence-in-depth: re-verify against committed key so a future framing-error refactor can't confirm on the
310 // wrong key.
311 if (!MAVLinkSigning::verifySignature(_op.keyBytes, message)) {
312 qCWarning(SigningControllerLog)
313 << "[ch" << _mavlinkChannel
314 << "] pending-enable HEARTBEAT signature did not verify against committed key";
315 return;
316 }
317 _confirmLocked();
318 }
319 } else if (_op.kind == OpKind::Disable) {
320 if (!MAVLinkSigning::isMessageSigned(message) && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
321 _op.unsignedSeen = true;
322 _confirmLocked();
323 }
324 }
325}
326
327void SigningController::_confirmLocked()
328{
329 // QTimer::stop is not thread-safe; route through queued invoke since processFrame may run on link thread.
330 QMetaObject::invokeMethod(&_timeout, "stop", Qt::AutoConnection);
331
332 if (_op.kind == OpKind::Enable) {
333 const QString confirmedName = _op.keyName;
334 if (!_channel.setSignOutgoing(true) || !_channel.setAcceptUnsignedCallback(MAVLinkSigning::callbackForPolicy(
336 const QString detail = tr("Signing confirmation received but local activation failed");
337 qCCritical(SigningControllerLog) << "[ch" << _mavlinkChannel << "]" << detail;
338 _failLocked(FailReason::InitFailed, detail);
339 return;
340 }
341 qCDebug(SigningControllerLog) << "[ch" << _mavlinkChannel << "] enable confirmed — key" << confirmedName;
342 _clearLocked();
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();
348 }
349}
350
351void SigningController::_completeDisableSuccessLocked()
352{
353 _channel.init(_mavlinkChannel, QByteArrayView(), nullptr);
354 _clearLocked();
355 QMetaObject::invokeMethod(this, [this]() { emit signingConfirmed(QString{}); }, Qt::AutoConnection);
356}
357
358void SigningController::_failLocked(FailReason reason, const QString& detail, bool cancelled)
359{
360 QMetaObject::invokeMethod(&_timeout, "stop", Qt::AutoConnection);
361
362 // Disable: if vehicle already sent an unsigned heartbeat before timeout/cancel, treat as success.
363 if (_op.kind == OpKind::Disable && _op.unsignedSeen && !cancelled) {
364 _completeDisableSuccessLocked();
365 return;
366 }
367
368 FailReason effectiveReason = reason;
369 QString effectiveDetail = detail;
370
371 if (_op.kind == OpKind::Enable) {
372 _channel.init(_mavlinkChannel, QByteArrayView(), nullptr);
373 } else if (_op.kind == OpKind::Disable) {
376 effectiveReason = FailReason::VehicleUnreachable;
377 effectiveDetail =
378 tr("Signing disable not confirmed — vehicle is unreachable or still requires signed messages. Local "
379 "signing remains enabled.");
380 }
381
382 qCWarning(SigningControllerLog) << "[ch" << _mavlinkChannel
383 << "] signing operation failed:" << failReasonName(effectiveReason)
384 << effectiveDetail;
385
386 SigningFailure failure{effectiveReason, effectiveDetail};
387 _clearLocked();
388 QMetaObject::invokeMethod(this, [this, failure]() { emit signingFailed(failure); }, Qt::AutoConnection);
389}
390
391void SigningController::cancelPending(const QString& detail)
392{
393 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
394 if (!_isPendingLocked()) {
395 return;
396 }
397 const QString effectiveDetail =
398 detail.isEmpty()
399 ? tr("Signing operation cancelled — primary link changed before vehicle confirmation")
400 : detail;
401 _failLocked(FailReason::VehicleUnreachable, effectiveDetail, /*cancelled=*/true);
402}
403
404void SigningController::_onTimeout()
405{
406 QMutexLocker<QRecursiveMutex> locker(&_fsmMutex);
407 if (!_isPendingLocked()) {
408 return;
409 }
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);
415}
416
417void SigningController::_clearLocked()
418{
419 _autoDetectGuard.reset();
420 QGC::secureZero(_op.keyBytes);
421 _setOpLocked(PendingOp{});
422}
mavlink_channel_t
mavlink_status_t * mavlink_get_channel_status(uint8_t chan)
Definition QGCMAVLink.cc:53
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)
QString keyHint() const
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.
int streamCount() const
bool isEnabled() const
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.
QString keyName() const
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)
QString statusText