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_DroneCAN/AP_DroneCAN_DNA_Server.cpp
Views: 1798
1
/*
2
* This file is free software: you can redistribute it and/or modify it
3
* under the terms of the GNU General Public License as published by the
4
* Free Software Foundation, either version 3 of the License, or
5
* (at your option) any later version.
6
*
7
* This file is distributed in the hope that it will be useful, but
8
* WITHOUT ANY WARRANTY; without even the implied warranty of
9
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10
* See the GNU General Public License for more details.
11
*
12
* You should have received a copy of the GNU General Public License along
13
* with this program. If not, see <http://www.gnu.org/licenses/>.
14
*
15
* Author: Siddharth Bharat Purohit
16
*/
17
18
#include <AP_HAL/AP_HAL.h>
19
20
#if HAL_ENABLE_DRONECAN_DRIVERS
21
22
#include "AP_DroneCAN_DNA_Server.h"
23
#include "AP_DroneCAN.h"
24
#include <StorageManager/StorageManager.h>
25
#include <AP_Math/AP_Math.h>
26
#include <GCS_MAVLink/GCS.h>
27
#include <AP_Logger/AP_Logger.h>
28
#include <AP_BoardConfig/AP_BoardConfig.h>
29
#include <stdio.h>
30
extern const AP_HAL::HAL& hal;
31
32
// FORMAT REVISION DREAMS (things to address if the NodeRecord needs to be changed substantially)
33
// * have DNA server accept only a 16 byte local UID to avoid overhead from variable sized hash
34
// * have a real empty flag for entries and/or use a CRC which is not zero for an input of all zeros
35
// * fix FNV-1a hash folding to be to 48 bits (6 bytes) instead of 56
36
37
#define NODERECORD_MAGIC 0xAC01
38
#define NODERECORD_MAGIC_LEN 2 // uint16_t
39
#define MAX_NODE_ID 125
40
#define NODERECORD_LOC(node_id) ((node_id * sizeof(NodeRecord)) + NODERECORD_MAGIC_LEN)
41
42
#define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0)
43
44
// database is currently shared by all DNA servers
45
AP_DroneCAN_DNA_Server::Database AP_DroneCAN_DNA_Server::db;
46
47
// initialize database (storage accessor is always replaced with the one supplied)
48
void AP_DroneCAN_DNA_Server::Database::init(StorageAccess *storage_)
49
{
50
// storage size must be synced with StorageCANDNA entry in StorageManager.cpp
51
static_assert(NODERECORD_LOC(MAX_NODE_ID+1) <= 1024, "DNA storage too small");
52
53
// might be called from multiple threads if multiple servers use the same database
54
WITH_SEMAPHORE(sem);
55
56
storage = storage_; // use supplied accessor
57
58
// validate magic number
59
uint16_t magic = storage->read_uint16(0);
60
if (magic != NODERECORD_MAGIC) {
61
reset(); // resetting the database will put the magic back
62
}
63
64
// check and note each possible node ID's registration's presence
65
for (uint8_t i = 1; i <= MAX_NODE_ID; i++) {
66
if (check_registration(i)) {
67
node_registered.set(i);
68
}
69
}
70
}
71
72
// remove all registrations from the database
73
void AP_DroneCAN_DNA_Server::Database::reset()
74
{
75
WITH_SEMAPHORE(sem);
76
77
NodeRecord record;
78
memset(&record, 0, sizeof(record));
79
node_registered.clearall();
80
81
// all-zero record means no registration
82
// ensure node ID 0 is cleared even if we can't use it so we know the state
83
for (uint8_t i = 0; i <= MAX_NODE_ID; i++) {
84
write_record(record, i);
85
}
86
87
// mark the magic at the start to indicate a valid (and reset) database
88
storage->write_uint16(0, NODERECORD_MAGIC);
89
}
90
91
// handle initializing the server with its own node ID and unique ID
92
void AP_DroneCAN_DNA_Server::Database::init_server(uint8_t own_node_id, const uint8_t own_unique_id[], uint8_t own_unique_id_len)
93
{
94
WITH_SEMAPHORE(sem);
95
96
// register server node ID and unique ID if not correctly registered. note
97
// that ardupilot mixes the node ID into the unique ID so changing the node
98
// ID will "leak" the old node ID
99
if (own_node_id != find_node_id(own_unique_id, own_unique_id_len)) {
100
register_uid(own_node_id, own_unique_id, own_unique_id_len);
101
}
102
}
103
104
// handle processing the node info message. returns true if from a duplicate node
105
bool AP_DroneCAN_DNA_Server::Database::handle_node_info(uint8_t source_node_id, const uint8_t unique_id[])
106
{
107
WITH_SEMAPHORE(sem);
108
109
if (is_registered(source_node_id)) {
110
// this device's node ID is associated with a different unique ID
111
if (source_node_id != find_node_id(unique_id, 16)) {
112
return true; // so raise as duplicate
113
}
114
} else {
115
register_uid(source_node_id, unique_id, 16); // we don't know about this node ID, let's register it
116
}
117
return false; // not a duplicate
118
}
119
120
// handle the allocation message. returns the allocated node ID, or 0 if allocation failed
121
uint8_t AP_DroneCAN_DNA_Server::Database::handle_allocation(const uint8_t unique_id[])
122
{
123
WITH_SEMAPHORE(sem);
124
125
uint8_t resp_node_id = find_node_id(unique_id, 16);
126
if (resp_node_id == 0) {
127
// find free node ID, starting at the max as prescribed by the standard
128
resp_node_id = MAX_NODE_ID;
129
while (resp_node_id > 0) {
130
if (!node_registered.get(resp_node_id)) {
131
break;
132
}
133
resp_node_id--;
134
}
135
136
if (resp_node_id != 0) {
137
create_registration(resp_node_id, unique_id, 16);
138
}
139
}
140
return resp_node_id; // will be 0 if not found and not created
141
}
142
143
// retrieve node ID that matches the given unique ID. returns 0 if not found
144
uint8_t AP_DroneCAN_DNA_Server::Database::find_node_id(const uint8_t unique_id[], uint8_t size)
145
{
146
NodeRecord record, cmp_record;
147
compute_uid_hash(cmp_record, unique_id, size);
148
149
for (int i = MAX_NODE_ID; i > 0; i--) {
150
if (node_registered.get(i)) {
151
read_record(record, i);
152
if (memcmp(record.uid_hash, cmp_record.uid_hash, sizeof(NodeRecord::uid_hash)) == 0) {
153
return i; // node ID found
154
}
155
}
156
}
157
return 0; // not found
158
}
159
160
// fill the given record with the hash of the given unique ID
161
void AP_DroneCAN_DNA_Server::Database::compute_uid_hash(NodeRecord &record, const uint8_t unique_id[], uint8_t size) const
162
{
163
uint64_t hash = FNV_1_OFFSET_BASIS_64;
164
hash_fnv_1a(size, unique_id, &hash);
165
166
// xor-folding per http://www.isthe.com/chongo/tech/comp/fnv/
167
hash = (hash>>56) ^ (hash&(((uint64_t)1<<56)-1)); // 56 should be 48 since we use 6 bytes
168
169
// write it to ret
170
for (uint8_t i=0; i<6; i++) {
171
record.uid_hash[i] = (hash >> (8*i)) & 0xff;
172
}
173
}
174
175
// register a given unique ID to a given node ID, deleting any existing registration for the unique ID
176
void AP_DroneCAN_DNA_Server::Database::register_uid(uint8_t node_id, const uint8_t unique_id[], uint8_t size)
177
{
178
uint8_t prev_node_id = find_node_id(unique_id, size); // have we registered this unique ID under a different node ID?
179
if (prev_node_id != 0) {
180
delete_registration(prev_node_id); // yes, delete old node ID's registration
181
}
182
// overwrite an existing registration with this node ID, if any
183
create_registration(node_id, unique_id, size);
184
}
185
186
// create the registration for the given node ID and set its record's unique ID
187
void AP_DroneCAN_DNA_Server::Database::create_registration(uint8_t node_id, const uint8_t unique_id[], uint8_t size)
188
{
189
NodeRecord record;
190
compute_uid_hash(record, unique_id, size);
191
// compute and store CRC of the record's data to validate it
192
record.crc = crc_crc8(record.uid_hash, sizeof(record.uid_hash));
193
194
write_record(record, node_id);
195
196
node_registered.set(node_id);
197
}
198
199
// delete the given node ID's registration
200
void AP_DroneCAN_DNA_Server::Database::delete_registration(uint8_t node_id)
201
{
202
if (node_id > MAX_NODE_ID) {
203
return;
204
}
205
206
NodeRecord record;
207
208
// all-zero record means no registration
209
memset(&record, 0, sizeof(record));
210
write_record(record, node_id);
211
node_registered.clear(node_id);
212
}
213
214
// return true if the given node ID has a registration
215
bool AP_DroneCAN_DNA_Server::Database::check_registration(uint8_t node_id)
216
{
217
NodeRecord record;
218
read_record(record, node_id);
219
220
uint8_t empty_uid[sizeof(NodeRecord::uid_hash)] {};
221
uint8_t crc = crc_crc8(record.uid_hash, sizeof(record.uid_hash));
222
if (crc == record.crc && memcmp(&record.uid_hash[0], &empty_uid[0], sizeof(empty_uid)) != 0) {
223
return true; // CRC matches and UID hash is not all zero
224
}
225
return false;
226
}
227
228
// read the given node ID's registration's record
229
void AP_DroneCAN_DNA_Server::Database::read_record(NodeRecord &record, uint8_t node_id)
230
{
231
if (node_id > MAX_NODE_ID) {
232
return;
233
}
234
235
storage->read_block(&record, NODERECORD_LOC(node_id), sizeof(NodeRecord));
236
}
237
238
// write the given node ID's registration's record
239
void AP_DroneCAN_DNA_Server::Database::write_record(const NodeRecord &record, uint8_t node_id)
240
{
241
if (node_id > MAX_NODE_ID) {
242
return;
243
}
244
245
storage->write_block(NODERECORD_LOC(node_id), &record, sizeof(NodeRecord));
246
}
247
248
249
AP_DroneCAN_DNA_Server::AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan, CanardInterface &canard_iface, uint8_t driver_index) :
250
storage(StorageManager::StorageCANDNA),
251
_ap_dronecan(ap_dronecan),
252
_canard_iface(canard_iface),
253
allocation_sub(allocation_cb, driver_index),
254
node_status_sub(node_status_cb, driver_index),
255
node_info_client(_canard_iface, node_info_cb) {}
256
257
/* Initialises Publishers for respective UAVCAN Instance
258
Also resets the Server Record in case there is a mismatch
259
between specified node id and unique id against the existing
260
Server Record. */
261
bool AP_DroneCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id)
262
{
263
//Read the details from AP_DroneCAN
264
server_state = HEALTHY;
265
266
db.init(&storage); // initialize the database with our accessor
267
268
if (_ap_dronecan.check_and_reset_option(AP_DroneCAN::Options::DNA_CLEAR_DATABASE)) {
269
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UC DNA database reset");
270
db.reset();
271
}
272
273
db.init_server(node_id, own_unique_id, own_unique_id_len);
274
275
/* Also add to seen node id this is to verify
276
if any duplicates are on the bus carrying our Node ID */
277
node_seen.set(node_id);
278
node_verified.set(node_id);
279
node_healthy.set(node_id);
280
self_node_id = node_id;
281
return true;
282
}
283
284
/* Run through the list of seen node ids for verification no more
285
than once per 5 second. We continually verify the nodes in our
286
seen list, So that we can raise issue if there are duplicates
287
on the bus. */
288
void AP_DroneCAN_DNA_Server::verify_nodes()
289
{
290
uint32_t now = AP_HAL::millis();
291
if ((now - last_verification_request) < 5000) {
292
return;
293
}
294
295
#if HAL_LOGGING_ENABLED
296
uint8_t log_count = AP::logger().get_log_start_count();
297
if (log_count != last_logging_count) {
298
last_logging_count = log_count;
299
node_logged.clearall();
300
}
301
#endif
302
303
//Check if we got acknowledgement from previous request
304
//except for requests using our own node_id
305
if (curr_verifying_node == self_node_id) {
306
nodeInfo_resp_rcvd = true;
307
}
308
309
if (!nodeInfo_resp_rcvd) {
310
/* Also notify GCS about this
311
Reason for this could be either the node was disconnected
312
Or a node with conflicting ID appeared and is sending response
313
at the same time. */
314
node_verified.clear(curr_verifying_node);
315
}
316
317
last_verification_request = now;
318
//Find the next registered Node ID to be verified.
319
for (uint8_t i = 0; i <= MAX_NODE_ID; i++) {
320
curr_verifying_node = (curr_verifying_node + 1) % (MAX_NODE_ID + 1);
321
if ((curr_verifying_node == self_node_id) || (curr_verifying_node == 0)) {
322
continue;
323
}
324
if (node_seen.get(curr_verifying_node)) {
325
break;
326
}
327
}
328
if (db.is_registered(curr_verifying_node)) {
329
uavcan_protocol_GetNodeInfoRequest request;
330
node_info_client.request(curr_verifying_node, request);
331
nodeInfo_resp_rcvd = false;
332
}
333
}
334
335
/* Handles Node Status Message, adds to the Seen Node list
336
Also starts the Service call for Node Info to complete the
337
Verification process. */
338
void AP_DroneCAN_DNA_Server::handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg)
339
{
340
if (transfer.source_node_id > MAX_NODE_ID || transfer.source_node_id == 0) {
341
return;
342
}
343
if ((msg.health != UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK ||
344
msg.mode != UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL) &&
345
!_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) {
346
//if node is not healthy or operational, clear resp health mask, and set fault_node_id
347
fault_node_id = transfer.source_node_id;
348
server_state = NODE_STATUS_UNHEALTHY;
349
node_healthy.clear(transfer.source_node_id);
350
} else {
351
node_healthy.set(transfer.source_node_id);
352
if (node_healthy == node_verified) {
353
server_state = HEALTHY;
354
}
355
}
356
if (!node_verified.get(transfer.source_node_id)) {
357
//immediately begin verification of the node_id
358
uavcan_protocol_GetNodeInfoRequest request;
359
node_info_client.request(transfer.source_node_id, request);
360
}
361
//Add node to seen list if not seen before
362
node_seen.set(transfer.source_node_id);
363
}
364
365
/* Node Info message handler
366
Handle responses from GetNodeInfo Request. We verify the node info
367
against our records. Marks Verification mask if already recorded,
368
Or register if the node id is available and not recorded for the
369
received Unique ID */
370
void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp)
371
{
372
if (transfer.source_node_id > MAX_NODE_ID || transfer.source_node_id == 0) {
373
return;
374
}
375
/*
376
if we haven't logged this node then log it now
377
*/
378
#if HAL_LOGGING_ENABLED
379
if (!node_logged.get(transfer.source_node_id) && AP::logger().logging_started()) {
380
node_logged.set(transfer.source_node_id);
381
uint64_t uid[2];
382
memcpy(uid, rsp.hardware_version.unique_id, sizeof(rsp.hardware_version.unique_id));
383
// @LoggerMessage: CAND
384
// @Description: Info from GetNodeInfo request
385
// @Field: TimeUS: Time since system startup
386
// @Field: Driver: Driver index
387
// @Field: NodeId: Node ID
388
// @Field: UID1: Hardware ID, part 1
389
// @Field: UID2: Hardware ID, part 2
390
// @Field: Name: Name string
391
// @Field: Major: major revision id
392
// @Field: Minor: minor revision id
393
// @Field: Version: AP_Periph git hash
394
AP::logger().Write("CAND", "TimeUS,Driver,NodeId,UID1,UID2,Name,Major,Minor,Version",
395
"s-#------", "F--------", "QBBQQZBBI",
396
AP_HAL::micros64(),
397
_ap_dronecan.get_driver_index(),
398
transfer.source_node_id,
399
uid[0], uid[1],
400
rsp.name.data,
401
rsp.software_version.major,
402
rsp.software_version.minor,
403
rsp.software_version.vcs_commit);
404
}
405
#endif
406
407
bool duplicate = db.handle_node_info(transfer.source_node_id, rsp.hardware_version.unique_id);
408
if (duplicate) {
409
if (!_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) {
410
/* This is a device with node_id already registered
411
for another device */
412
server_state = DUPLICATE_NODES;
413
fault_node_id = transfer.source_node_id;
414
memcpy(fault_node_name, rsp.name.data, sizeof(fault_node_name));
415
}
416
} else {
417
//Verify as well
418
node_verified.set(transfer.source_node_id);
419
if (transfer.source_node_id == curr_verifying_node) {
420
nodeInfo_resp_rcvd = true;
421
}
422
}
423
}
424
425
// process node ID allocation messages for DNA
426
void AP_DroneCAN_DNA_Server::handle_allocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg)
427
{
428
if (transfer.source_node_id != 0) {
429
return; // ignore allocation messages that are not DNA requests
430
}
431
uint32_t now = AP_HAL::millis();
432
433
if ((now - last_alloc_msg_ms) > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_FOLLOWUP_TIMEOUT_MS) {
434
rcvd_unique_id_offset = 0; // reset state, timed out
435
}
436
437
if (msg.first_part_of_unique_id) {
438
// nodes waiting to send a follow up will instead send a first part
439
// again if they see another allocation message. therefore we should
440
// always reset and process a received first part, since any node we
441
// were allocating will never send its follow up and we'd just time out
442
rcvd_unique_id_offset = 0;
443
} else if (rcvd_unique_id_offset == 0) {
444
return; // not first part but we are expecting one, ignore
445
}
446
447
if (rcvd_unique_id_offset) {
448
debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %lu -- Accepting Followup part! %u\n",
449
(unsigned long)now,
450
unsigned((now - last_alloc_msg_ms)));
451
} else {
452
debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %lu -- Accepting First part! %u\n",
453
(unsigned long)now,
454
unsigned((now - last_alloc_msg_ms)));
455
}
456
457
last_alloc_msg_ms = now;
458
if ((rcvd_unique_id_offset + msg.unique_id.len) > sizeof(rcvd_unique_id)) {
459
rcvd_unique_id_offset = 0; // reset state, request contains an over-long ID
460
return;
461
}
462
463
// save the new portion of the unique ID
464
memcpy(&rcvd_unique_id[rcvd_unique_id_offset], msg.unique_id.data, msg.unique_id.len);
465
rcvd_unique_id_offset += msg.unique_id.len;
466
467
// respond with the message containing the received unique ID so far, or
468
// with the node ID if we successfully allocated one
469
uavcan_protocol_dynamic_node_id_Allocation rsp {};
470
memcpy(rsp.unique_id.data, rcvd_unique_id, rcvd_unique_id_offset);
471
rsp.unique_id.len = rcvd_unique_id_offset;
472
473
if (rcvd_unique_id_offset == sizeof(rcvd_unique_id)) { // full unique ID received, allocate it!
474
// we ignore the preferred node ID as it seems nobody uses the feature
475
// and we couldn't guarantee it anyway. we will always remember and
476
// re-assign node IDs consistently, so the node could send a status
477
// with a particular ID once then switch back to no preference for DNA
478
rsp.node_id = db.handle_allocation(rcvd_unique_id);
479
rcvd_unique_id_offset = 0; // reset state for next allocation
480
if (rsp.node_id == 0) { // allocation failed
481
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DroneCAN DNA allocation failed; database full");
482
// don't send reply with a failed ID in case the allocatee does
483
// silly things, though it is technically legal. the allocatee will
484
// then time out and try again (though we still won't have an ID!)
485
return;
486
}
487
}
488
489
allocation_pub.broadcast(rsp, false); // never publish allocation message with CAN FD
490
}
491
492
//report the server state, along with failure message if any
493
bool AP_DroneCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) const
494
{
495
switch (server_state) {
496
case HEALTHY:
497
return true;
498
case DUPLICATE_NODES: {
499
if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) {
500
// ignore error
501
return true;
502
}
503
snprintf(fail_msg, fail_msg_len, "Duplicate Node %s../%d!", fault_node_name, fault_node_id);
504
return false;
505
}
506
case NODE_STATUS_UNHEALTHY: {
507
if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) {
508
// ignore error
509
return true;
510
}
511
snprintf(fail_msg, fail_msg_len, "Node %d unhealthy!", fault_node_id);
512
return false;
513
}
514
}
515
// should never get; compiler should enforce all server_states are covered
516
return false;
517
}
518
519
#endif //HAL_NUM_CAN_IFACES
520
521