3#include <QtCore/QByteArrayView>
4#include <QtCore/QDeadlineTimer>
5#include <QtCore/QReadWriteLock>
6#include <QtCore/QString>
34 uint64_t persistedTimestamp = 0,
const QString& keyName = {},
bool signOutgoing =
true);
77 bool setSignOutgoing(
bool signOutgoing);
79 mavlink_signing_t _signing{};
81 mavlink_signing_streams_t _streams{};
83 bool _enabled =
false;
85 std::atomic<bool> _autoDetectSuspended{
false};
86 QDeadlineTimer _detectCooldown;
87 mavlink_signing_status_t _lastTransitionStatus = MAVLINK_SIGNING_STATUS_NONE;
88 mutable QReadWriteLock _lock;
RAII guard for an atomic suspend flag: sets on construction, clears on destruction.
Owns MAVLink signing state for one channel: signing/streams structs, key hint, and RW lock.
bool init(mavlink_channel_t channel, QByteArrayView key, mavlink_accept_unsigned_t callback, uint64_t persistedTimestamp=0, const QString &keyName={}, bool signOutgoing=true)
SigningChannel(SigningChannel &&)=delete
void setKeyHint(const QString &name)
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.
SigningChannel & operator=(const SigningChannel &)=delete
MAVLinkSigning::DetectSnapshot detectSnapshot() const
Single-lock snapshot; 3 separate reads have TOCTOU window vs MockLink's thread.
static constexpr uint64_t kPersistedTimestampSafetyBumpTicks
60s post-reboot timestamp bump (matches ArduPilot GCS_Signing.cpp); absorbs SIGKILL/suspend/NTP/clock...
void clearDetectCooldown()
bool isAutoDetectSuspended() const
While suspended, tryDetectKey is suppressed to block stale-key installs during pending enable.
bool consumeStatusTransition(mavlink_channel_t channel)
True if last_status changed since previous call; sole transition-detection source.
SigningChannel(const SigningChannel &)=delete
SigningChannel & operator=(SigningChannel &&)=delete
bool isInDetectCooldown() const
Throttles detect misses; HMAC per packet per key is expensive. Monotonic timer to avoid wall-clock sk...
static constexpr qint64 kDetectCooldownMs
TimestampSnapshot currentTimestampAndName() const
Returns current timestamp and active key name. Returns {0, ""} when signing is not enabled.
~SigningChannel()=default
Owns MAVLink signing state and the deferred-confirmation state machine for one LinkInterface.
Single-lock snapshot struct; fields populated by SigningChannel::detectSnapshot().