Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Bootloader/can.cpp
9326 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
16
CAN bootloader support
17
*/
18
#include <AP_HAL/AP_HAL.h>
19
#include <hal.h>
20
#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES
21
#include <AP_Math/AP_Math.h>
22
#include <AP_Math/crc.h>
23
#include <canard.h>
24
#include "support.h"
25
#include <dronecan_msgs.h>
26
#include "can.h"
27
#include "bl_protocol.h"
28
#include <drivers/stm32/canard_stm32.h>
29
#include "app_comms.h"
30
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
31
#include <stdio.h>
32
#include <AP_HAL_ChibiOS/CANIface.h>
33
#include <AP_CheckFirmware/AP_CheckFirmware.h>
34
35
static CanardInstance canard;
36
static uint32_t canard_memory_pool[4096/4];
37
#ifndef HAL_CAN_DEFAULT_NODE_ID
38
#define HAL_CAN_DEFAULT_NODE_ID CANARD_BROADCAST_NODE_ID
39
#endif
40
static uint8_t initial_node_id = HAL_CAN_DEFAULT_NODE_ID;
41
42
// can config for 1MBit
43
static uint32_t baudrate = 1000000U;
44
45
#if HAL_USE_CAN
46
static CANConfig cancfg = {
47
CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_TXFP,
48
0 // filled in below
49
};
50
// pipelining is not faster when using ChibiOS CAN driver
51
#define FW_UPDATE_PIPELINE_LEN 1
52
#else
53
ChibiOS::CANIface can_iface[HAL_NUM_CAN_IFACES];
54
#endif
55
56
#ifndef CAN_APP_VERSION_MAJOR
57
#define CAN_APP_VERSION_MAJOR 2
58
#endif
59
#ifndef CAN_APP_VERSION_MINOR
60
#define CAN_APP_VERSION_MINOR 0
61
#endif
62
#ifndef CAN_APP_NODE_NAME
63
#define CAN_APP_NODE_NAME "org.ardupilot." CHIBIOS_BOARD_NAME
64
#endif
65
66
#ifdef EXT_FLASH_SIZE_MB
67
static_assert(EXT_FLASH_SIZE_MB == 0, "DroneCAN bootloader cannot support external flash");
68
#endif
69
70
static uint8_t node_id_allocation_transfer_id;
71
static uavcan_protocol_NodeStatus node_status;
72
static uint32_t send_next_node_id_allocation_request_at_ms;
73
static uint8_t node_id_allocation_unique_id_offset;
74
75
static void processTx(void);
76
77
// keep up to 4 transfers in progress
78
#ifndef FW_UPDATE_PIPELINE_LEN
79
#define FW_UPDATE_PIPELINE_LEN 4
80
#endif
81
82
#if CH_CFG_USE_MUTEXES == TRUE
83
static HAL_Semaphore can_mutex;
84
#endif
85
86
static struct {
87
uint32_t rtt_ms;
88
uint32_t ofs;
89
uint8_t node_id;
90
uint8_t path[sizeof(uavcan_protocol_file_Path::path.data)+1];
91
uint8_t sector;
92
uint32_t sector_ofs;
93
uint8_t transfer_id;
94
uint8_t idx;
95
struct {
96
uint8_t tx_id;
97
uint32_t sent_ms;
98
uint32_t offset;
99
bool have_reply;
100
uavcan_protocol_file_ReadResponse pkt;
101
} reads[FW_UPDATE_PIPELINE_LEN];
102
uint16_t erased_to;
103
} fw_update;
104
105
/*
106
get cpu unique ID
107
*/
108
static void readUniqueID(uint8_t* out_uid)
109
{
110
uint8_t len = sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data);
111
memset(out_uid, 0, len);
112
memcpy(out_uid, (const void *)UDID_START, MIN(len,12));
113
}
114
115
/*
116
simple 16 bit random number generator
117
*/
118
static uint16_t get_randomu16(void)
119
{
120
static uint32_t m_z = 1234;
121
static uint32_t m_w = 76542;
122
m_z = 36969 * (m_z & 0xFFFFu) + (m_z >> 16);
123
m_w = 18000 * (m_w & 0xFFFFu) + (m_w >> 16);
124
return ((m_z << 16) + m_w) & 0xFFFF;
125
}
126
127
128
/**
129
* Returns a pseudo random integer in a given range
130
*/
131
static uint32_t get_random_range(uint16_t range)
132
{
133
return get_randomu16() % range;
134
}
135
136
/*
137
handle a GET_NODE_INFO request
138
*/
139
static void handle_get_node_info(CanardInstance* ins,
140
CanardRxTransfer* transfer)
141
{
142
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
143
uavcan_protocol_GetNodeInfoResponse pkt {};
144
145
node_status.uptime_sec = AP_HAL::millis() / 1000U;
146
147
pkt.status = node_status;
148
pkt.software_version.major = CAN_APP_VERSION_MAJOR;
149
pkt.software_version.minor = CAN_APP_VERSION_MINOR;
150
151
readUniqueID(pkt.hardware_version.unique_id);
152
153
// use hw major/minor for APJ_BOARD_ID so we know what fw is
154
// compatible with this hardware
155
pkt.hardware_version.major = APJ_BOARD_ID >> 8;
156
pkt.hardware_version.minor = APJ_BOARD_ID & 0xFF;
157
158
char name[strlen(CAN_APP_NODE_NAME)+1];
159
strcpy(name, CAN_APP_NODE_NAME);
160
pkt.name.len = strlen(CAN_APP_NODE_NAME);
161
memcpy(pkt.name.data, name, pkt.name.len);
162
163
uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer, true);
164
165
canardRequestOrRespond(ins,
166
transfer->source_node_id,
167
UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE,
168
UAVCAN_PROTOCOL_GETNODEINFO_ID,
169
&transfer->transfer_id,
170
transfer->priority,
171
CanardResponse,
172
&buffer[0],
173
total_size);
174
}
175
176
/*
177
send a read for a fw update
178
*/
179
static bool send_fw_read(uint8_t idx)
180
{
181
auto &r = fw_update.reads[idx];
182
r.tx_id = fw_update.transfer_id;
183
r.have_reply = false;
184
185
uavcan_protocol_file_ReadRequest pkt {};
186
pkt.path.path.len = strlen((const char *)fw_update.path);
187
pkt.offset = r.offset;
188
memcpy(pkt.path.path.data, fw_update.path, pkt.path.path.len);
189
190
uint8_t buffer[UAVCAN_PROTOCOL_FILE_READ_REQUEST_MAX_SIZE];
191
uint16_t total_size = uavcan_protocol_file_ReadRequest_encode(&pkt, buffer, true);
192
193
if (canardRequestOrRespond(&canard,
194
fw_update.node_id,
195
UAVCAN_PROTOCOL_FILE_READ_SIGNATURE,
196
UAVCAN_PROTOCOL_FILE_READ_ID,
197
&fw_update.transfer_id,
198
CANARD_TRANSFER_PRIORITY_HIGH,
199
CanardRequest,
200
&buffer[0],
201
total_size) > 0) {
202
// mark it as having been sent
203
r.sent_ms = AP_HAL::millis();
204
return true;
205
}
206
return false;
207
}
208
209
/*
210
send a read for a fw update
211
*/
212
static void send_fw_reads(void)
213
{
214
const uint32_t now = AP_HAL::millis();
215
216
for (uint8_t i=0; i<FW_UPDATE_PIPELINE_LEN; i++) {
217
const uint8_t idx = (fw_update.idx+i) % FW_UPDATE_PIPELINE_LEN;
218
const auto &r = fw_update.reads[idx];
219
if (r.have_reply) {
220
continue;
221
}
222
if (r.sent_ms != 0 && now - r.sent_ms < 10+2*MAX(250,fw_update.rtt_ms)) {
223
// waiting on a response
224
continue;
225
}
226
if (!send_fw_read(idx)) {
227
break;
228
}
229
}
230
}
231
232
/*
233
erase up to at least the given sector number
234
*/
235
static void erase_to(uint16_t sector)
236
{
237
if (sector < fw_update.erased_to) {
238
return;
239
}
240
flash_func_erase_sector(sector);
241
fw_update.erased_to = sector+1;
242
243
/*
244
pre-erase any non-erased pages up to end of flash. This puts all
245
the load of erasing at the start of flashing which is much
246
faster than flashing as we go on boards with small flash
247
sectors. We stop at the first already erased page so we don't
248
end up wasting time erasing already erased pages when the
249
firmware is much smaller than the total flash size
250
*/
251
while (flash_func_sector_size(fw_update.erased_to) != 0 &&
252
!flash_func_is_erased(fw_update.erased_to)) {
253
flash_func_erase_sector(fw_update.erased_to);
254
fw_update.erased_to++;
255
}
256
}
257
258
/*
259
handle response to file read for fw update
260
*/
261
static void handle_file_read_response(CanardInstance* ins, CanardRxTransfer* transfer)
262
{
263
if (transfer->source_node_id != fw_update.node_id) {
264
return;
265
}
266
/*
267
match the response to a sent request
268
*/
269
uint8_t idx = 0;
270
bool found = false;
271
for (idx=0; idx<FW_UPDATE_PIPELINE_LEN; idx++) {
272
const auto &r = fw_update.reads[idx];
273
if (r.tx_id == transfer->transfer_id) {
274
found = true;
275
break;
276
}
277
}
278
if (!found) {
279
// not a current transfer, we may be getting long delays
280
fw_update.rtt_ms = MIN(3000, fw_update.rtt_ms+250);
281
return;
282
}
283
if (uavcan_protocol_file_ReadResponse_decode(transfer, &fw_update.reads[idx].pkt)) {
284
return;
285
}
286
fw_update.reads[idx].have_reply = true;
287
uint32_t rtt = MIN(3000,MAX(AP_HAL::millis() - fw_update.reads[idx].sent_ms, 25));
288
fw_update.rtt_ms = uint32_t(0.9 * fw_update.rtt_ms + 0.1 * rtt);
289
290
while (fw_update.reads[fw_update.idx].have_reply) {
291
auto &r = fw_update.reads[fw_update.idx];
292
if (r.offset != fw_update.ofs) {
293
// bad sequence
294
r.have_reply = false;
295
r.sent_ms = 0;
296
break;
297
}
298
const auto &pkt = r.pkt;
299
const uint16_t len = pkt.data.len;
300
const uint16_t len_words = (len+3U)/4U;
301
const uint8_t *buf = (uint8_t *)pkt.data.data;
302
uint32_t buf32[len_words] {};
303
memcpy((uint8_t*)buf32, buf, len);
304
305
if (fw_update.ofs == 0) {
306
flash_set_keep_unlocked(true);
307
}
308
309
const uint32_t sector_size = flash_func_sector_size(fw_update.sector);
310
if (sector_size == 0) {
311
// firmware is too big
312
fw_update.node_id = 0;
313
flash_write_flush();
314
flash_set_keep_unlocked(false);
315
node_status.vendor_specific_status_code = uint8_t(check_fw_result_t::FAIL_REASON_BAD_LENGTH_APP);
316
break;
317
}
318
if (fw_update.sector_ofs == 0) {
319
erase_to(fw_update.sector);
320
}
321
if (fw_update.sector_ofs+len > sector_size) {
322
erase_to(fw_update.sector+1);
323
}
324
if (!flash_write_buffer(fw_update.ofs, buf32, len_words)) {
325
continue;
326
}
327
328
fw_update.ofs += len;
329
fw_update.sector_ofs += len;
330
if (fw_update.sector_ofs >= flash_func_sector_size(fw_update.sector)) {
331
fw_update.sector++;
332
fw_update.sector_ofs -= sector_size;
333
}
334
335
if (len < sizeof(uavcan_protocol_file_ReadResponse::data.data)) {
336
fw_update.node_id = 0;
337
flash_write_flush();
338
flash_set_keep_unlocked(false);
339
#if AP_CHECK_FIRMWARE_ENABLED
340
const auto ok = check_good_firmware();
341
#else
342
const auto ok = check_fw_result_t::CHECK_FW_OK;
343
#endif
344
node_status.vendor_specific_status_code = uint8_t(ok);
345
if (ok == check_fw_result_t::CHECK_FW_OK) {
346
jump_to_app();
347
}
348
return;
349
}
350
351
r.have_reply = false;
352
r.sent_ms = 0;
353
r.offset += FW_UPDATE_PIPELINE_LEN*sizeof(uavcan_protocol_file_ReadResponse::data.data);
354
send_fw_read(fw_update.idx);
355
processTx();
356
357
fw_update.idx = (fw_update.idx + 1) % FW_UPDATE_PIPELINE_LEN;
358
}
359
360
// show offset number we are flashing in kbyte as crude progress indicator
361
node_status.vendor_specific_status_code = 1 + (fw_update.ofs / 1024U);
362
}
363
364
/*
365
handle a begin firmware update request. We start pulling in the file data
366
*/
367
static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* transfer)
368
{
369
if (fw_update.node_id == 0) {
370
uavcan_protocol_file_BeginFirmwareUpdateRequest pkt;
371
if (uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(transfer, &pkt)) {
372
return;
373
}
374
if (pkt.image_file_remote_path.path.len > sizeof(fw_update.path)-1) {
375
return;
376
}
377
memset(&fw_update, 0, sizeof(fw_update));
378
for (uint8_t i=0; i<FW_UPDATE_PIPELINE_LEN; i++) {
379
fw_update.reads[i].offset = i*sizeof(uavcan_protocol_file_ReadResponse::data.data);
380
}
381
memcpy(fw_update.path, pkt.image_file_remote_path.path.data, pkt.image_file_remote_path.path.len);
382
fw_update.path[pkt.image_file_remote_path.path.len] = 0;
383
fw_update.node_id = pkt.source_node_id;
384
if (fw_update.node_id == 0) {
385
fw_update.node_id = transfer->source_node_id;
386
}
387
}
388
389
uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE];
390
uavcan_protocol_file_BeginFirmwareUpdateResponse reply {};
391
reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK;
392
393
uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer, true);
394
canardRequestOrRespond(ins,
395
transfer->source_node_id,
396
UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE,
397
UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID,
398
&transfer->transfer_id,
399
transfer->priority,
400
CanardResponse,
401
&buffer[0],
402
total_size);
403
}
404
405
static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* transfer)
406
{
407
// Rule C - updating the randomized time interval
408
send_next_node_id_allocation_request_at_ms =
409
AP_HAL::millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
410
get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
411
412
if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID)
413
{
414
node_id_allocation_unique_id_offset = 0;
415
return;
416
}
417
418
struct uavcan_protocol_dynamic_node_id_Allocation msg;
419
if (uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg)) {
420
return;
421
}
422
423
// Obtaining the local unique ID
424
uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)];
425
readUniqueID(my_unique_id);
426
427
// Matching the received UID against the local one
428
if (memcmp(msg.unique_id.data, my_unique_id, msg.unique_id.len) != 0) {
429
node_id_allocation_unique_id_offset = 0;
430
return; // No match, return
431
}
432
433
if (msg.unique_id.len < sizeof(msg.unique_id.data)) {
434
// The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout.
435
node_id_allocation_unique_id_offset = msg.unique_id.len;
436
send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS;
437
} else if (msg.node_id != CANARD_BROADCAST_NODE_ID) { // new ID valid? (if not we will time out and start over)
438
// Allocation complete - copying the allocated node ID from the message
439
canardSetLocalNodeID(ins, msg.node_id);
440
}
441
}
442
443
/**
444
* This callback is invoked by the library when a new message or request or response is received.
445
*/
446
static void onTransferReceived(CanardInstance* ins,
447
CanardRxTransfer* transfer)
448
{
449
/*
450
* Dynamic node ID allocation protocol.
451
* Taking this branch only if we don't have a node ID, ignoring otherwise.
452
*/
453
if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID) {
454
if (transfer->transfer_type == CanardTransferTypeBroadcast &&
455
transfer->data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
456
handle_allocation_response(ins, transfer);
457
}
458
return;
459
}
460
461
switch (transfer->data_type_id) {
462
case UAVCAN_PROTOCOL_GETNODEINFO_ID:
463
handle_get_node_info(ins, transfer);
464
break;
465
466
case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:
467
handle_begin_firmware_update(ins, transfer);
468
break;
469
470
case UAVCAN_PROTOCOL_FILE_READ_ID:
471
handle_file_read_response(ins, transfer);
472
break;
473
474
case UAVCAN_PROTOCOL_RESTARTNODE_ID:
475
NVIC_SystemReset();
476
break;
477
}
478
}
479
480
481
/**
482
* This callback is invoked by the library when it detects beginning of a new transfer on the bus that can be received
483
* by the local node.
484
* If the callback returns true, the library will receive the transfer.
485
* If the callback returns false, the library will ignore the transfer.
486
* All transfers that are addressed to other nodes are always ignored.
487
*/
488
static bool shouldAcceptTransfer(const CanardInstance* ins,
489
uint64_t* out_data_type_signature,
490
uint16_t data_type_id,
491
CanardTransferType transfer_type,
492
uint8_t source_node_id)
493
{
494
(void)source_node_id;
495
496
if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID) {
497
/*
498
* If we're in the process of allocation of dynamic node ID, accept only relevant transfers.
499
*/
500
if ((transfer_type == CanardTransferTypeBroadcast) &&
501
(data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID))
502
{
503
*out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE;
504
return true;
505
}
506
return false;
507
}
508
509
switch (data_type_id) {
510
case UAVCAN_PROTOCOL_GETNODEINFO_ID:
511
*out_data_type_signature = UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE;
512
return true;
513
case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:
514
*out_data_type_signature = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE;
515
return true;
516
case UAVCAN_PROTOCOL_RESTARTNODE_ID:
517
*out_data_type_signature = UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE;
518
return true;
519
case UAVCAN_PROTOCOL_FILE_READ_ID:
520
*out_data_type_signature = UAVCAN_PROTOCOL_FILE_READ_SIGNATURE;
521
return true;
522
default:
523
break;
524
}
525
526
return false;
527
}
528
529
#if HAL_USE_CAN
530
static void processTx(void)
531
{
532
static uint8_t fail_count;
533
for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) {
534
CANTxFrame txmsg {};
535
txmsg.DLC = txf->data_len;
536
memcpy(txmsg.data8, txf->data, 8);
537
txmsg.EID = txf->id & CANARD_CAN_EXT_ID_MASK;
538
txmsg.IDE = 1;
539
txmsg.RTR = 0;
540
if (canTransmit(&CAND1, CAN_ANY_MAILBOX, &txmsg, TIME_IMMEDIATE) == MSG_OK) {
541
canardPopTxQueue(&canard);
542
fail_count = 0;
543
} else {
544
// just exit and try again later. If we fail 8 times in a row
545
// then start discarding to prevent the pool filling up
546
if (fail_count < 8) {
547
fail_count++;
548
} else {
549
canardPopTxQueue(&canard);
550
}
551
return;
552
}
553
}
554
}
555
556
static void processRx(void)
557
{
558
CANRxFrame rxmsg {};
559
while (canReceive(&CAND1, CAN_ANY_MAILBOX, &rxmsg, TIME_IMMEDIATE) == MSG_OK) {
560
CanardCANFrame rx_frame {};
561
562
#ifdef HAL_GPIO_PIN_LED_BOOTLOADER
563
palToggleLine(HAL_GPIO_PIN_LED_BOOTLOADER);
564
#endif
565
const uint64_t timestamp = AP_HAL::micros64();
566
memcpy(rx_frame.data, rxmsg.data8, 8);
567
rx_frame.data_len = rxmsg.DLC;
568
if(rxmsg.IDE) {
569
rx_frame.id = CANARD_CAN_FRAME_EFF | rxmsg.EID;
570
} else {
571
rx_frame.id = rxmsg.SID;
572
}
573
canardHandleRxFrame(&canard, &rx_frame, timestamp);
574
}
575
}
576
#else
577
// Use HAL CAN interface
578
static void processTx(void)
579
{
580
static uint8_t fail_count;
581
for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) {
582
AP_HAL::CANFrame txmsg {};
583
txmsg.dlc = txf->data_len;
584
memcpy(txmsg.data, txf->data, 8);
585
txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF);
586
// push message with 1s timeout
587
bool send_ok = false;
588
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
589
send_ok |= (can_iface[i].send(txmsg, AP_HAL::micros64() + 1000000, 0) > 0);
590
}
591
if (send_ok) {
592
canardPopTxQueue(&canard);
593
fail_count = 0;
594
} else {
595
// just exit and try again later. If we fail 8 times in a row
596
// then start discarding to prevent the pool filling up
597
if (fail_count < 8) {
598
fail_count++;
599
} else {
600
canardPopTxQueue(&canard);
601
}
602
return;
603
}
604
}
605
}
606
607
static void processRx(void)
608
{
609
AP_HAL::CANFrame rxmsg;
610
while (true) {
611
bool got_pkt = false;
612
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
613
bool read_select = true;
614
bool write_select = false;
615
can_iface[i].select(read_select, write_select, nullptr, 0);
616
if (!read_select) {
617
continue;
618
}
619
#ifdef HAL_GPIO_PIN_LED_BOOTLOADER
620
palToggleLine(HAL_GPIO_PIN_LED_BOOTLOADER);
621
#endif
622
CanardCANFrame rx_frame {};
623
624
//palToggleLine(HAL_GPIO_PIN_LED);
625
uint64_t timestamp;
626
AP_HAL::CANIface::CanIOFlags flags;
627
can_iface[i].receive(rxmsg, timestamp, flags);
628
memcpy(rx_frame.data, rxmsg.data, 8);
629
rx_frame.data_len = rxmsg.dlc;
630
rx_frame.id = rxmsg.id;
631
canardHandleRxFrame(&canard, &rx_frame, timestamp);
632
got_pkt = true;
633
}
634
if (!got_pkt) {
635
break;
636
}
637
}
638
}
639
#endif //#if HAL_USE_CAN
640
641
/*
642
wrapper around broadcast
643
*/
644
static void canard_broadcast(uint64_t data_type_signature,
645
uint16_t data_type_id,
646
uint8_t &transfer_id,
647
uint8_t priority,
648
const void* payload,
649
uint16_t payload_len)
650
{
651
#if CH_CFG_USE_MUTEXES == TRUE
652
WITH_SEMAPHORE(can_mutex);
653
#endif
654
canardBroadcast(&canard,
655
data_type_signature,
656
data_type_id,
657
&transfer_id,
658
priority,
659
payload,
660
payload_len);
661
}
662
663
664
/*
665
handle waiting for a node ID
666
*/
667
static void can_handle_DNA(void)
668
{
669
if (canardGetLocalNodeID(&canard) != CANARD_BROADCAST_NODE_ID) {
670
return;
671
}
672
673
if (AP_HAL::millis() < send_next_node_id_allocation_request_at_ms) {
674
return;
675
}
676
677
send_next_node_id_allocation_request_at_ms =
678
AP_HAL::millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
679
get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
680
681
// Structure of the request is documented in the DSDL definition
682
// See http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation
683
uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1];
684
allocation_request[0] = (uint8_t)(CANARD_BROADCAST_NODE_ID << 1U);
685
686
if (node_id_allocation_unique_id_offset == 0) {
687
allocation_request[0] |= 1; // First part of unique ID
688
}
689
690
uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)];
691
readUniqueID(my_unique_id);
692
693
static const uint8_t MaxLenOfUniqueIDInRequest = 6;
694
uint8_t uid_size = (uint8_t)(sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data) - node_id_allocation_unique_id_offset);
695
if (uid_size > MaxLenOfUniqueIDInRequest) {
696
uid_size = MaxLenOfUniqueIDInRequest;
697
}
698
699
memmove(&allocation_request[1], &my_unique_id[node_id_allocation_unique_id_offset], uid_size);
700
701
// Broadcasting the request
702
canard_broadcast(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE,
703
UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID,
704
node_id_allocation_transfer_id,
705
CANARD_TRANSFER_PRIORITY_LOW,
706
&allocation_request[0],
707
(uint16_t) (uid_size + 1));
708
709
// Preparing for timeout; if response is received, this value will be updated from the callback.
710
node_id_allocation_unique_id_offset = 0;
711
}
712
713
static void send_node_status(void)
714
{
715
uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE];
716
node_status.uptime_sec = AP_HAL::millis() / 1000U;
717
718
uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer, true);
719
720
static uint8_t transfer_id; // Note that the transfer ID variable MUST BE STATIC (or heap-allocated)!
721
722
canard_broadcast(UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE,
723
UAVCAN_PROTOCOL_NODESTATUS_ID,
724
transfer_id,
725
CANARD_TRANSFER_PRIORITY_LOW,
726
buffer,
727
len);
728
}
729
730
731
/**
732
* This function is called at 1 Hz rate from the main loop.
733
*/
734
static void process1HzTasks(uint64_t timestamp_usec)
735
{
736
canardCleanupStaleTransfers(&canard, timestamp_usec);
737
738
if (canardGetLocalNodeID(&canard) != CANARD_BROADCAST_NODE_ID) {
739
node_status.mode = fw_update.node_id?UAVCAN_PROTOCOL_NODESTATUS_MODE_SOFTWARE_UPDATE:UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE;
740
send_node_status();
741
}
742
}
743
744
void can_set_node_id(uint8_t node_id)
745
{
746
initial_node_id = node_id;
747
}
748
749
// check for a firmware update marker left by app
750
bool can_check_update(void)
751
{
752
bool ret = false;
753
#if HAL_RAM_RESERVE_START >= 256
754
struct app_bootloader_comms *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
755
if (comms->magic == APP_BOOTLOADER_COMMS_MAGIC && comms->my_node_id != 0) {
756
can_set_node_id(comms->my_node_id);
757
fw_update.node_id = comms->server_node_id;
758
for (uint8_t i=0; i<FW_UPDATE_PIPELINE_LEN; i++) {
759
fw_update.reads[i].offset = i*sizeof(uavcan_protocol_file_ReadResponse::data.data);
760
}
761
memcpy(fw_update.path, comms->path, sizeof(uavcan_protocol_file_Path::path.data)+1);
762
ret = true;
763
// clear comms region
764
memset(comms, 0, sizeof(struct app_bootloader_comms));
765
}
766
#endif
767
#if defined(CAN1_BASE) && defined(RCC_APB1ENR_CAN1EN)
768
// check for px4 fw update. px4 uses the filter registers in CAN1
769
// to communicate with the bootloader. This only works on CAN1
770
if (!ret && stm32_was_software_reset()) {
771
uint32_t *fir = (uint32_t *)(CAN1_BASE + 0x240);
772
struct PACKED app_shared {
773
union {
774
uint64_t ull;
775
uint32_t ul[2];
776
uint8_t valid;
777
} crc;
778
uint32_t signature;
779
uint32_t bus_speed;
780
uint32_t node_id;
781
} *app = (struct app_shared *)&fir[4];
782
/* we need to enable the CAN peripheral in order to look at
783
the FIR registers.
784
*/
785
RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
786
static const uint32_t app_signature = 0xb0a04150;
787
if (app->signature == app_signature &&
788
app->node_id > 0 && app->node_id < 128) {
789
// crc is in reversed word order in FIR registers
790
uint32_t sig[3];
791
memcpy((uint8_t *)&sig[0], (const uint8_t *)&app->signature, sizeof(sig));
792
const uint64_t crc = crc_crc64(sig, 3);
793
const uint32_t *crc32 = (const uint32_t *)&crc;
794
if (crc32[0] == app->crc.ul[1] &&
795
crc32[1] == app->crc.ul[0]) {
796
// reset signature so we don't get in a boot loop
797
app->signature = 0;
798
// setup node ID
799
can_set_node_id(app->node_id);
800
// and baudrate
801
baudrate = app->bus_speed;
802
ret = true;
803
}
804
}
805
}
806
#endif
807
return ret;
808
}
809
810
void can_start()
811
{
812
#if AP_CHECK_FIRMWARE_ENABLED
813
node_status.vendor_specific_status_code = uint8_t(check_good_firmware());
814
#else
815
node_status.vendor_specific_status_code = uint8_t(check_fw_result_t::CHECK_FW_OK);
816
#endif
817
node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE;
818
819
#if HAL_USE_CAN
820
// calculate optimal CAN timings given PCLK1 and baudrate
821
CanardSTM32CANTimings timings {};
822
canardSTM32ComputeCANTimings(STM32_PCLK1, baudrate, &timings);
823
cancfg.btr = CAN_BTR_SJW(0) |
824
CAN_BTR_TS2(timings.bit_segment_2-1) |
825
CAN_BTR_TS1(timings.bit_segment_1-1) |
826
CAN_BTR_BRP(timings.bit_rate_prescaler-1);
827
canStart(&CAND1, &cancfg);
828
#else
829
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
830
can_iface[i].init(baudrate);
831
}
832
#endif
833
canardInit(&canard, (uint8_t *)canard_memory_pool, sizeof(canard_memory_pool),
834
onTransferReceived, shouldAcceptTransfer, NULL);
835
836
if (initial_node_id != CANARD_BROADCAST_NODE_ID) {
837
canardSetLocalNodeID(&canard, initial_node_id);
838
}
839
840
send_next_node_id_allocation_request_at_ms =
841
AP_HAL::millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
842
get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
843
844
if (stm32_was_watchdog_reset()) {
845
node_status.vendor_specific_status_code = uint8_t(check_fw_result_t::FAIL_REASON_WATCHDOG);
846
}
847
848
{
849
/*
850
support termination solder bridge or switch and optional LED
851
*/
852
#if defined(HAL_GPIO_PIN_GPIO_CAN1_TERM) && defined(HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH)
853
const bool can1_term = palReadLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH);
854
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, can1_term);
855
# ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM_LED
856
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_LED, can1_term? HAL_LED_ON : !HAL_LED_ON);
857
# endif
858
#endif
859
860
#if defined(HAL_GPIO_PIN_GPIO_CAN2_TERM) && defined(HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH)
861
const bool can2_term = palReadLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH);
862
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, can2_term);
863
# ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM_LED
864
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_LED, can2_term? HAL_LED_ON : !HAL_LED_ON);
865
# endif
866
#endif
867
868
#if defined(HAL_GPIO_PIN_GPIO_CAN3_TERM) && defined(HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH)
869
const bool can3_term = palReadLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH);
870
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, can3_term);
871
# ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM_LED
872
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_LED, can3_term? HAL_LED_ON : !HAL_LED_ON);
873
# endif
874
#endif
875
}
876
}
877
878
879
void can_update()
880
{
881
// do one loop of CAN support. If we are doing a firmware update
882
// then loop until it is finished
883
do {
884
processTx();
885
processRx();
886
can_handle_DNA();
887
static uint32_t last_1Hz_ms;
888
uint32_t now = AP_HAL::millis();
889
if (now - last_1Hz_ms >= 1000) {
890
last_1Hz_ms = now;
891
process1HzTasks(AP_HAL::micros64());
892
}
893
if (fw_update.node_id != 0) {
894
send_fw_reads();
895
}
896
#if CH_CFG_ST_FREQUENCY >= 1000000
897
// give a bit of time for background processing
898
chThdSleepMicroseconds(200);
899
#endif
900
} while (fw_update.node_id != 0);
901
}
902
903
// printf to CAN LogMessage for debugging
904
void can_vprintf(const char *fmt, va_list ap)
905
{
906
// only on H7 for now, where we have plenty of flash
907
#if defined(STM32H7)
908
uavcan_protocol_debug_LogMessage pkt {};
909
uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];
910
uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap);
911
pkt.text.len = MIN(n, sizeof(pkt.text.data));
912
913
uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer, true);
914
static uint8_t logmsg_transfer_id;
915
916
canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE,
917
UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID,
918
logmsg_transfer_id,
919
CANARD_TRANSFER_PRIORITY_LOW,
920
buffer,
921
len);
922
#endif // defined(STM32H7)
923
}
924
925
// printf to CAN LogMessage for debugging
926
void can_printf(const char *fmt, ...)
927
{
928
// only on H7 for now, where we have plenty of flash
929
#if defined(STM32H7)
930
va_list ap;
931
va_start(ap, fmt);
932
can_vprintf(fmt, ap);
933
va_end(ap);
934
#endif // defined(STM32H7)
935
}
936
937
void can_printf_severity(uint8_t severity, const char *fmt, ...)
938
{
939
// only on H7 for now, where we have plenty of flash
940
#if defined(STM32H7)
941
va_list ap;
942
va_start(ap, fmt);
943
can_vprintf(fmt, ap);
944
va_end(ap);
945
#endif
946
}
947
948
949
#endif // HAL_USE_CAN
950
951