CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp
Views: 1798
1
/*
2
support checking board ID and firmware CRC in the bootloader
3
*/
4
#include "AP_CheckFirmware.h"
5
#include <AP_HAL/HAL.h>
6
7
#if AP_CHECK_FIRMWARE_ENABLED && AP_SIGNED_FIRMWARE && !defined(HAL_BOOTLOADER_BUILD)
8
9
#include "monocypher.h"
10
#include <AP_Math/AP_Math.h>
11
12
#if HAL_GCS_ENABLED
13
#include <GCS_MAVLink/GCS.h>
14
#endif
15
16
extern const AP_HAL::HAL &hal;
17
18
/*
19
find public keys in bootloader, or return NULL if signature not found
20
21
this assumes the public keys are in the first sector
22
*/
23
const struct ap_secure_data *AP_CheckFirmware::find_public_keys(void)
24
{
25
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
26
const uint32_t page_size = hal.flash->getpagesize(0);
27
const uint32_t flash_addr = hal.flash->getpageaddr(0);
28
const uint8_t *flash = (const uint8_t *)flash_addr;
29
const uint8_t key[] = AP_PUBLIC_KEY_SIGNATURE;
30
return (const struct ap_secure_data *)memmem(flash, page_size, key, sizeof(key));
31
#else
32
return nullptr;
33
#endif
34
}
35
36
/*
37
return true if all keys are zeros
38
*/
39
bool AP_CheckFirmware::all_zero_keys(const struct ap_secure_data *sec_data)
40
{
41
const uint8_t zero_key[AP_PUBLIC_KEY_LEN] {};
42
/*
43
look over all public keys, if one matches then we are OK
44
*/
45
for (const auto &public_key : sec_data->public_key) {
46
if (memcmp(public_key.key, zero_key, AP_PUBLIC_KEY_LEN) != 0) {
47
return false;
48
}
49
}
50
return true;
51
}
52
53
54
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
55
/*
56
return true if 1k of data is all 0xff (empty flash)
57
*/
58
static bool empty_1k(const uint8_t *data)
59
{
60
for (uint32_t i=0; i<1024; i++) {
61
if (data[i] != 0xFFU) {
62
return false;
63
}
64
}
65
return true;
66
}
67
#endif
68
69
/*
70
read bootloader into memory. This is complicated by the potential presence
71
of persistent data from temperature calibration at the end of the sector
72
73
Also note this assumes the public keys are in the first sector if
74
the bootloader covers more than one sector. This is a reasonable
75
assumption given the linker file
76
*/
77
AP_CheckFirmware::bl_data *AP_CheckFirmware::read_bootloader(void)
78
{
79
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
80
struct bl_data *bld = NEW_NOTHROW bl_data;
81
if (bld == nullptr) {
82
return nullptr;
83
}
84
const uint32_t page_size = hal.flash->getpagesize(0);
85
const uint32_t flash_addr = hal.flash->getpageaddr(0);
86
const uint8_t *flash = (uint8_t *)flash_addr;
87
const uint16_t block_size = 1024;
88
uint16_t num_blocks = page_size / block_size;
89
/*
90
find first empty block
91
*/
92
for (uint16_t i=0; i<num_blocks; i++) {
93
if (empty_1k(&flash[block_size*i])) {
94
break;
95
}
96
bld->length1 += block_size;
97
}
98
bld->data1 = NEW_NOTHROW uint8_t[bld->length1];
99
if (bld->data1 == nullptr) {
100
delete bld;
101
return nullptr;
102
}
103
memcpy(bld->data1, flash, bld->length1);
104
flash += bld->length1;
105
num_blocks -= bld->length1 / block_size;
106
107
/*
108
find first non-empty block, which should be the persistent data if-any
109
*/
110
bld->offset2 = bld->length1;
111
while (num_blocks > 0) {
112
if (!empty_1k(&flash[bld->offset2])) {
113
break;
114
}
115
num_blocks--;
116
bld->offset2 += block_size;
117
}
118
if (num_blocks > 0) {
119
// we have persistent data to save
120
bld->length2 = num_blocks * block_size;
121
bld->data2 = NEW_NOTHROW uint8_t[bld->length2];
122
if (bld->data2 == nullptr) {
123
delete bld;
124
return nullptr;
125
}
126
memcpy(bld->data2, &flash[bld->offset2], bld->length2);
127
}
128
return bld;
129
#else
130
return nullptr;
131
#endif
132
}
133
134
#if HAL_GCS_ENABLED
135
uint8_t AP_CheckFirmware::session_key[8];
136
137
/*
138
make a session key
139
*/
140
static void make_session_key(uint8_t key[8])
141
{
142
struct {
143
uint32_t time_us;
144
uint8_t unique_id[12];
145
uint16_t rand1;
146
uint16_t rand2;
147
} data {};
148
static_assert(sizeof(data) % 4 == 0, "data must be multiple of 4 bytes");
149
150
// get data which will not apply on a different board, and includes some randomness
151
uint8_t uid_len = 12;
152
hal.util->get_system_id_unformatted(data.unique_id, uid_len);
153
data.time_us = AP_HAL::micros();
154
data.rand1 = get_random16();
155
data.rand2 = get_random16();
156
const uint64_t c64 = crc_crc64((const uint32_t *)&data, sizeof(data)/sizeof(uint32_t));
157
memcpy(key, (uint8_t *)&c64, 8);
158
}
159
160
161
/*
162
write bootloader from memory
163
*/
164
bool AP_CheckFirmware::write_bootloader(const struct bl_data *bld)
165
{
166
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
167
const uint32_t flash_addr = hal.flash->getpageaddr(0);
168
EXPECT_DELAY_MS(3000);
169
if (!hal.flash->erasepage(0)) {
170
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader erase failed");
171
return false;
172
}
173
EXPECT_DELAY_MS(3000);
174
if (!hal.flash->write(flash_addr, bld->data1, bld->length1)) {
175
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader write1 failed");
176
return false;
177
}
178
EXPECT_DELAY_MS(3000);
179
if (bld->length2 != 0 &&
180
!hal.flash->write(flash_addr+bld->offset2, bld->data2, bld->length2)) {
181
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader write1 failed");
182
return false;
183
}
184
return true;
185
#else
186
return false;
187
#endif
188
}
189
190
/*
191
check signature in a command against bootloader public keys
192
*/
193
bool AP_CheckFirmware::check_signature(const mavlink_secure_command_t &pkt)
194
{
195
const struct ap_secure_data *sec_data = find_public_keys();
196
if (sec_data == nullptr) {
197
return false;
198
}
199
if (all_zero_keys(sec_data)) {
200
// allow through if no keys are setup
201
return true;
202
}
203
if (pkt.sig_length != 64) {
204
// monocypher signatures are 64 bytes
205
return false;
206
}
207
/*
208
look over all public keys, if one matches then we are OK
209
*/
210
for (const auto &public_key : sec_data->public_key) {
211
crypto_check_ctx ctx {};
212
crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx;
213
crypto_check_init(actx, &pkt.data[pkt.data_length], public_key.key);
214
215
crypto_check_update(actx, (const uint8_t*)&pkt.sequence, sizeof(pkt.sequence));
216
crypto_check_update(actx, (const uint8_t*)&pkt.operation, sizeof(pkt.operation));
217
crypto_check_update(actx, pkt.data, pkt.data_length);
218
if (pkt.operation != SECURE_COMMAND_GET_SESSION_KEY) {
219
crypto_check_update(actx, session_key, sizeof(session_key));
220
}
221
if (crypto_check_final(actx) == 0) {
222
// good signature
223
return true;
224
}
225
}
226
return false;
227
}
228
229
/*
230
set public keys in bootloader
231
*/
232
bool AP_CheckFirmware::set_public_keys(uint8_t key_idx, uint8_t num_keys, const uint8_t *key_data)
233
{
234
auto *bld = read_bootloader();
235
if (bld == nullptr) {
236
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Failed to load bootloader into memory");
237
return false;
238
}
239
const uint8_t key[] = AP_PUBLIC_KEY_SIGNATURE;
240
struct ap_secure_data *sec_data = (struct ap_secure_data *)memmem(bld->data1, bld->length1, key, sizeof(key));
241
if (sec_data == nullptr) {
242
delete bld;
243
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Failed to find key signature");
244
return false;
245
}
246
memcpy(sec_data->public_key[key_idx].key, key_data, num_keys*AP_PUBLIC_KEY_LEN);
247
248
/*
249
pack so non-zero keys are at the start
250
*/
251
const uint8_t zero_key[AP_PUBLIC_KEY_LEN] {};
252
uint8_t max_keys = AP_PUBLIC_KEY_MAX_KEYS;
253
for (uint8_t i=0; max_keys>1 && i<max_keys-1; i++) {
254
if (memcmp(zero_key, sec_data->public_key[i].key, AP_PUBLIC_KEY_LEN) == 0) {
255
memmove(sec_data->public_key[i].key, sec_data->public_key[i+1].key, AP_PUBLIC_KEY_LEN*(max_keys-(i+1)));
256
max_keys--;
257
i--;
258
}
259
}
260
memset(sec_data->public_key[max_keys-1].key, 0, AP_PUBLIC_KEY_LEN*(AP_PUBLIC_KEY_MAX_KEYS-max_keys));
261
262
bool ret = write_bootloader(bld);
263
delete bld;
264
return ret;
265
}
266
267
/*
268
handle a SECURE_COMMAND
269
*/
270
void AP_CheckFirmware::handle_secure_command(mavlink_channel_t chan, const mavlink_secure_command_t &pkt)
271
{
272
mavlink_secure_command_reply_t reply {};
273
reply.result = MAV_RESULT_UNSUPPORTED;
274
reply.sequence = pkt.sequence;
275
reply.operation = pkt.operation;
276
277
if (uint16_t(pkt.data_length) + uint16_t(pkt.sig_length) > sizeof(pkt.data)) {
278
reply.result = MAV_RESULT_DENIED;
279
goto send_reply;
280
}
281
if (!check_signature(pkt)) {
282
reply.result = MAV_RESULT_DENIED;
283
goto send_reply;
284
}
285
286
switch (pkt.operation) {
287
288
case SECURE_COMMAND_GET_SESSION_KEY: {
289
make_session_key(session_key);
290
reply.data_length = sizeof(session_key);
291
memcpy(reply.data, session_key, reply.data_length);
292
reply.result = MAV_RESULT_ACCEPTED;
293
break;
294
}
295
296
case SECURE_COMMAND_GET_PUBLIC_KEYS: {
297
const struct ap_secure_data *sec_data = find_public_keys();
298
if (pkt.data_length != 2) {
299
reply.result = MAV_RESULT_UNSUPPORTED;
300
goto send_reply;
301
}
302
const uint8_t key_idx = pkt.data[0];
303
uint8_t num_keys = pkt.data[1];
304
const uint8_t max_fetch = (sizeof(reply.data)-1) / AP_PUBLIC_KEY_LEN;
305
if (key_idx >= AP_PUBLIC_KEY_MAX_KEYS ||
306
num_keys > max_fetch ||
307
key_idx+num_keys > AP_PUBLIC_KEY_MAX_KEYS ||
308
sec_data == nullptr) {
309
reply.result = MAV_RESULT_FAILED;
310
goto send_reply;
311
}
312
313
// remove zero keys
314
const uint8_t zero_key[AP_PUBLIC_KEY_LEN] {};
315
while (num_keys > 0 &&
316
memcmp(zero_key, &sec_data->public_key[key_idx+num_keys-1], AP_PUBLIC_KEY_LEN) == 0) {
317
num_keys--;
318
}
319
320
reply.data_length = 1+num_keys*AP_PUBLIC_KEY_LEN;
321
reply.data[0] = key_idx;
322
memcpy(&reply.data[1], &sec_data->public_key[key_idx], reply.data_length-1);
323
reply.result = MAV_RESULT_ACCEPTED;
324
break;
325
}
326
327
case SECURE_COMMAND_SET_PUBLIC_KEYS: {
328
if (pkt.data_length < AP_PUBLIC_KEY_LEN+1) {
329
reply.result = MAV_RESULT_FAILED;
330
goto send_reply;
331
}
332
const uint8_t key_idx = pkt.data[0];
333
const uint8_t num_keys = (pkt.data_length-1) / AP_PUBLIC_KEY_LEN;
334
if (num_keys == 0) {
335
reply.result = MAV_RESULT_FAILED;
336
goto send_reply;
337
}
338
if (key_idx >= AP_PUBLIC_KEY_MAX_KEYS ||
339
key_idx+num_keys > AP_PUBLIC_KEY_MAX_KEYS) {
340
reply.result = MAV_RESULT_FAILED;
341
goto send_reply;
342
}
343
if (set_public_keys(key_idx, num_keys, &pkt.data[1])) {
344
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader update OK");
345
reply.result = MAV_RESULT_ACCEPTED;
346
} else {
347
reply.result = MAV_RESULT_FAILED;
348
}
349
break;
350
}
351
352
case SECURE_COMMAND_REMOVE_PUBLIC_KEYS: {
353
if (pkt.data_length != 2) {
354
reply.result = MAV_RESULT_FAILED;
355
goto send_reply;
356
}
357
const uint8_t key_idx = pkt.data[0];
358
const uint8_t num_keys = pkt.data[1];
359
if (num_keys == 0) {
360
reply.result = MAV_RESULT_FAILED;
361
goto send_reply;
362
}
363
if (key_idx >= AP_PUBLIC_KEY_MAX_KEYS ||
364
key_idx+num_keys > AP_PUBLIC_KEY_MAX_KEYS) {
365
reply.result = MAV_RESULT_FAILED;
366
goto send_reply;
367
}
368
uint8_t *data = NEW_NOTHROW uint8_t[num_keys*AP_PUBLIC_KEY_LEN];
369
if (data == nullptr) {
370
reply.result = MAV_RESULT_FAILED;
371
goto send_reply;
372
}
373
if (set_public_keys(key_idx, num_keys, data)) {
374
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader update OK");
375
reply.result = MAV_RESULT_ACCEPTED;
376
} else {
377
reply.result = MAV_RESULT_FAILED;
378
}
379
delete[] data;
380
break;
381
}
382
}
383
384
send_reply:
385
// send reply
386
mavlink_msg_secure_command_reply_send_struct(chan, &reply);
387
}
388
389
/*
390
implement secure command operations for updating public keys
391
*/
392
void AP_CheckFirmware::handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg)
393
{
394
switch (msg.msgid) {
395
case MAVLINK_MSG_ID_SECURE_COMMAND: {
396
mavlink_secure_command_t pkt;
397
mavlink_msg_secure_command_decode(&msg, &pkt);
398
handle_secure_command(chan, pkt);
399
break;
400
}
401
}
402
}
403
404
#endif // HAL_GCS_ENABLED
405
406
/*
407
check that a bootloader is OK to flash. We don't want to allow
408
flashing of a bootloader unless we either have no public keys setup
409
or the bootloader has public keys embedded. This prevents an easy
410
mistake of including an insecure bootloader in ROMFS with a secure build
411
*/
412
bool AP_CheckFirmware::check_signed_bootloader(const uint8_t *fw, uint32_t fw_size)
413
{
414
const struct ap_secure_data *sec_data = find_public_keys();
415
if (sec_data == nullptr || all_zero_keys(sec_data)) {
416
// current bootloader doesn't have public keys, so OK to load any bootloader
417
return true;
418
}
419
const uint8_t key[] = AP_PUBLIC_KEY_SIGNATURE;
420
sec_data = (const struct ap_secure_data *)memmem(fw, fw_size, key, sizeof(key));
421
if (sec_data == nullptr || all_zero_keys(sec_data)) {
422
// new bootloader doesn't have any public keys, not allowed
423
return false;
424
}
425
return true;
426
}
427
428
#endif // AP_CHECK_FIRMWARE_ENABLED
429
430