26 #define SIGNING_KEY_MAGIC 0x3852fcd1 43 if (_signing_storage.size() <
sizeof(key)) {
46 return _signing_storage.write_block(0, &key,
sizeof(key));
51 if (_signing_storage.size() <
sizeof(key)) {
54 if (!_signing_storage.read_block(&key, 0,
sizeof(key))) {
69 mavlink_setup_signing_t packet;
70 mavlink_msg_setup_signing_decode(msg, &packet);
77 if (!signing_key_save(key)) {
93 MAVLINK_MSG_ID_RADIO_STATUS,
99 if (status == mavlink_get_channel_status(MAVLINK_COMM_0)) {
104 for (uint8_t i=0; i<
ARRAY_SIZE(accept_list); i++) {
105 if (accept_list[i] == msgId) {
119 if (!signing_key_load(key)) {
122 mavlink_status_t *status = mavlink_get_channel_status(
chan);
123 if (status ==
nullptr) {
124 hal.
console->
printf(
"Failed to load signing key - no status");
127 memcpy(signing.secret_key, key.
secret_key, 32);
128 signing.link_id = (uint8_t)
chan;
132 signing.timestamp = key.
timestamp + 60UL * 100UL * 1000UL;
133 signing.flags = MAVLINK_SIGNING_FLAG_SIGN_OUTGOING;
138 for (uint8_t i=0; i<
sizeof(key.
secret_key); i++) {
139 if (signing.secret_key[i] != 0) {
146 mavlink_status_t *cstatus = mavlink_get_channel_status((mavlink_channel_t)(MAVLINK_COMM_0 + i));
147 if (cstatus !=
nullptr) {
150 cstatus->signing =
nullptr;
151 cstatus->signing_streams =
nullptr;
153 cstatus->signing = &signing;
154 cstatus->signing_streams = &signing_streams;
166 uint64_t signing_timestamp = (timestamp_usec / (1000*1000ULL));
168 const uint64_t epoch_offset = 1420070400;
169 if (signing_timestamp > epoch_offset) {
170 signing_timestamp -= epoch_offset;
174 signing_timestamp *= 100 * 1000ULL;
178 mavlink_channel_t
chan = (mavlink_channel_t)(MAVLINK_COMM_0 + i);
179 mavlink_status_t *status = mavlink_get_channel_status(chan);
180 if (status && status->signing && status->signing->timestamp < signing_timestamp) {
181 status->signing->timestamp = signing_timestamp;
186 save_signing_timestamp(
true);
197 if (!force_save_now && now - last_signing_save_ms < 30*1000UL) {
201 last_signing_save_ms = now;
204 if (!signing_key_load(key)) {
207 bool need_save =
false;
210 mavlink_channel_t
chan = (mavlink_channel_t)(MAVLINK_COMM_0 + i);
211 const mavlink_status_t *status = mavlink_get_channel_status(chan);
212 if (status && status->signing && status->signing->timestamp > key.
timestamp) {
213 key.
timestamp = status->signing->timestamp;
219 signing_key_save(key);
228 const mavlink_status_t *status = mavlink_get_channel_status(
chan);
229 if (status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) {
245 uint8_t reserved_space = 0;
246 if (reserve_param_space_start_ms != 0 &&
248 reserved_space = 100;
250 reserve_param_space_start_ms = 0;
253 const mavlink_status_t *status = mavlink_get_channel_status(chan);
254 if (status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) {
255 return MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN + reserved_space;
257 return MAVLINK_NUM_NON_PAYLOAD_BYTES + reserved_space;
AP_HAL::UARTDriver * console
Interface definition for the various Ground Control System.
static bool accept_unsigned_callback(const mavlink_status_t *status, uint32_t msgId)
bool signing_enabled(void) const
static uint8_t packet_overhead_chan(mavlink_channel_t chan)
static uint32_t last_signing_save_ms
virtual void printf(const char *,...) FMT_PRINTF(2
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static StorageAccess _signing_storage
#define SIGNING_KEY_MAGIC
void handle_setup_signing(const mavlink_message_t *msg)
AP_HAL::AnalogSource * chan
void load_signing_key(void)
static void save_signing_timestamp(bool force_save_now)
static mavlink_signing_streams_t signing_streams
static bool signing_key_save(const struct SigningKey &key)
static bool signing_key_load(struct SigningKey &key)
static void update_signing_timestamp(uint64_t timestamp_usec)
#define MAVLINK_COMM_NUM_BUFFERS
static const uint32_t accept_list[]