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_Canard_iface.cpp
Views: 1798
1
#include "AP_Canard_iface.h"
2
#include <AP_HAL/AP_HAL.h>
3
#include <AP_CANManager/AP_CANManager.h>
4
#if HAL_ENABLE_DRONECAN_DRIVERS
5
#include <canard/handler_list.h>
6
#include <canard/transfer_object.h>
7
#include <AP_Math/AP_Math.h>
8
#include <dronecan_msgs.h>
9
extern const AP_HAL::HAL& hal;
10
#define LOG_TAG "DroneCANIface"
11
#include <canard.h>
12
#include <AP_CANManager/AP_CANSensor.h>
13
14
#define DEBUG_PKTS 0
15
16
#define CANARD_MSG_TYPE_FROM_ID(x) ((uint16_t)(((x) >> 8U) & 0xFFFFU))
17
18
DEFINE_HANDLER_LIST_HEADS();
19
DEFINE_HANDLER_LIST_SEMAPHORES();
20
21
DEFINE_TRANSFER_OBJECT_HEADS();
22
DEFINE_TRANSFER_OBJECT_SEMAPHORES();
23
24
#if AP_TEST_DRONECAN_DRIVERS
25
CanardInterface* CanardInterface::canard_ifaces[] = {nullptr, nullptr, nullptr};
26
CanardInterface CanardInterface::test_iface{2};
27
uint8_t test_node_mem_area[1024];
28
HAL_Semaphore test_iface_sem;
29
#endif
30
31
void canard_allocate_sem_take(CanardPoolAllocator *allocator) {
32
if (allocator->semaphore == nullptr) {
33
allocator->semaphore = NEW_NOTHROW HAL_Semaphore;
34
if (allocator->semaphore == nullptr) {
35
// out of memory
36
CANARD_ASSERT(0);
37
return;
38
}
39
}
40
((HAL_Semaphore*)allocator->semaphore)->take_blocking();
41
}
42
43
void canard_allocate_sem_give(CanardPoolAllocator *allocator) {
44
if (allocator->semaphore == nullptr) {
45
// it should have been allocated by canard_allocate_sem_take
46
CANARD_ASSERT(0);
47
return;
48
}
49
((HAL_Semaphore*)allocator->semaphore)->give();
50
}
51
52
CanardInterface::CanardInterface(uint8_t iface_index) :
53
Interface(iface_index) {
54
#if AP_TEST_DRONECAN_DRIVERS
55
if (iface_index < 3) {
56
canard_ifaces[iface_index] = this;
57
}
58
if (iface_index == 0) {
59
test_iface.init(test_node_mem_area, sizeof(test_node_mem_area), 125);
60
}
61
canardInitTxTransfer(&tx_transfer);
62
#endif
63
}
64
65
void CanardInterface::init(void* mem_arena, size_t mem_arena_size, uint8_t node_id) {
66
canardInit(&canard, mem_arena, mem_arena_size, onTransferReception, shouldAcceptTransfer, this);
67
canardSetLocalNodeID(&canard, node_id);
68
initialized = true;
69
}
70
71
bool CanardInterface::broadcast(const Canard::Transfer &bcast_transfer) {
72
if (!initialized) {
73
return false;
74
}
75
WITH_SEMAPHORE(_sem_tx);
76
77
#if AP_TEST_DRONECAN_DRIVERS
78
if (this == &test_iface) {
79
test_iface_sem.take_blocking();
80
}
81
#endif
82
83
tx_transfer = {
84
.transfer_type = bcast_transfer.transfer_type,
85
.data_type_signature = bcast_transfer.data_type_signature,
86
.data_type_id = bcast_transfer.data_type_id,
87
.inout_transfer_id = bcast_transfer.inout_transfer_id,
88
.priority = bcast_transfer.priority,
89
.payload = (const uint8_t*)bcast_transfer.payload,
90
.payload_len = uint16_t(bcast_transfer.payload_len),
91
#if CANARD_ENABLE_CANFD
92
.canfd = bcast_transfer.canfd,
93
#endif
94
.deadline_usec = AP_HAL::micros64() + (bcast_transfer.timeout_ms * 1000),
95
#if CANARD_MULTI_IFACE
96
.iface_mask = uint8_t((1<<num_ifaces) - 1),
97
#endif
98
};
99
// do canard broadcast
100
int16_t ret = canardBroadcastObj(&canard, &tx_transfer);
101
#if AP_TEST_DRONECAN_DRIVERS
102
if (this == &test_iface) {
103
test_iface_sem.give();
104
}
105
#endif
106
if (ret <= 0) {
107
protocol_stats.tx_errors++;
108
} else {
109
protocol_stats.tx_frames += ret;
110
}
111
return ret > 0;
112
}
113
114
bool CanardInterface::request(uint8_t destination_node_id, const Canard::Transfer &req_transfer) {
115
if (!initialized) {
116
return false;
117
}
118
WITH_SEMAPHORE(_sem_tx);
119
120
tx_transfer = {
121
.transfer_type = req_transfer.transfer_type,
122
.data_type_signature = req_transfer.data_type_signature,
123
.data_type_id = req_transfer.data_type_id,
124
.inout_transfer_id = req_transfer.inout_transfer_id,
125
.priority = req_transfer.priority,
126
.payload = (const uint8_t*)req_transfer.payload,
127
.payload_len = uint16_t(req_transfer.payload_len),
128
#if CANARD_ENABLE_CANFD
129
.canfd = req_transfer.canfd,
130
#endif
131
.deadline_usec = AP_HAL::micros64() + (req_transfer.timeout_ms * 1000),
132
#if CANARD_MULTI_IFACE
133
.iface_mask = uint8_t((1<<num_ifaces) - 1),
134
#endif
135
};
136
// do canard request
137
int16_t ret = canardRequestOrRespondObj(&canard, destination_node_id, &tx_transfer);
138
if (ret <= 0) {
139
protocol_stats.tx_errors++;
140
} else {
141
protocol_stats.tx_frames += ret;
142
}
143
return ret > 0;
144
}
145
146
bool CanardInterface::respond(uint8_t destination_node_id, const Canard::Transfer &res_transfer) {
147
if (!initialized) {
148
return false;
149
}
150
WITH_SEMAPHORE(_sem_tx);
151
152
tx_transfer = {
153
.transfer_type = res_transfer.transfer_type,
154
.data_type_signature = res_transfer.data_type_signature,
155
.data_type_id = res_transfer.data_type_id,
156
.inout_transfer_id = res_transfer.inout_transfer_id,
157
.priority = res_transfer.priority,
158
.payload = (const uint8_t*)res_transfer.payload,
159
.payload_len = uint16_t(res_transfer.payload_len),
160
#if CANARD_ENABLE_CANFD
161
.canfd = res_transfer.canfd,
162
#endif
163
.deadline_usec = AP_HAL::micros64() + (res_transfer.timeout_ms * 1000),
164
#if CANARD_MULTI_IFACE
165
.iface_mask = uint8_t((1<<num_ifaces) - 1),
166
#endif
167
};
168
// do canard respond
169
int16_t ret = canardRequestOrRespondObj(&canard, destination_node_id, &tx_transfer);
170
if (ret <= 0) {
171
protocol_stats.tx_errors++;
172
} else {
173
protocol_stats.tx_frames += ret;
174
}
175
return ret > 0;
176
}
177
178
void CanardInterface::onTransferReception(CanardInstance* ins, CanardRxTransfer* transfer) {
179
CanardInterface* iface = (CanardInterface*) ins->user_reference;
180
iface->handle_message(*transfer);
181
}
182
183
bool CanardInterface::shouldAcceptTransfer(const CanardInstance* ins,
184
uint64_t* out_data_type_signature,
185
uint16_t data_type_id,
186
CanardTransferType transfer_type,
187
uint8_t source_node_id) {
188
CanardInterface* iface = (CanardInterface*) ins->user_reference;
189
return iface->accept_message(data_type_id, *out_data_type_signature);
190
}
191
192
#if AP_TEST_DRONECAN_DRIVERS
193
void CanardInterface::processTestRx() {
194
if (!test_iface.initialized) {
195
return;
196
}
197
WITH_SEMAPHORE(test_iface_sem);
198
for (const CanardCANFrame* txf = canardPeekTxQueue(&test_iface.canard); txf != NULL; txf = canardPeekTxQueue(&test_iface.canard)) {
199
if (canard_ifaces[0]) {
200
canardHandleRxFrame(&canard_ifaces[0]->canard, txf, AP_HAL::micros64());
201
}
202
canardPopTxQueue(&test_iface.canard);
203
}
204
}
205
#endif
206
207
void CanardInterface::processTx(bool raw_commands_only = false) {
208
WITH_SEMAPHORE(_sem_tx);
209
210
for (uint8_t iface = 0; iface < num_ifaces; iface++) {
211
if (ifaces[iface] == NULL) {
212
continue;
213
}
214
auto txq = canard.tx_queue;
215
if (txq == nullptr) {
216
return;
217
}
218
// volatile as the value can change at any time during can interrupt
219
// we need to ensure that this is not optimized
220
volatile const auto *stats = ifaces[iface]->get_statistics();
221
uint64_t last_transmit_us = stats==nullptr?0:stats->last_transmit_us;
222
bool iface_down = true;
223
if (stats == nullptr || (AP_HAL::micros64() - last_transmit_us) < 200000UL) {
224
/*
225
We were not able to queue the frame for
226
sending. Only mark the send as failing if the
227
interface is active. We consider an interface as
228
active if it has had successful transmits for some time.
229
*/
230
iface_down = false;
231
}
232
// scan through list of pending transfers
233
while (true) {
234
auto txf = &txq->frame;
235
if (raw_commands_only &&
236
CANARD_MSG_TYPE_FROM_ID(txf->id) != UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID &&
237
CANARD_MSG_TYPE_FROM_ID(txf->id) != COM_HOBBYWING_ESC_RAWCOMMAND_ID) {
238
// look at next transfer
239
txq = txq->next;
240
if (txq == nullptr) {
241
break;
242
}
243
continue;
244
}
245
AP_HAL::CANFrame txmsg {};
246
txmsg.dlc = AP_HAL::CANFrame::dataLengthToDlc(txf->data_len);
247
memcpy(txmsg.data, txf->data, txf->data_len);
248
txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF);
249
#if HAL_CANFD_SUPPORTED
250
txmsg.canfd = txf->canfd;
251
#endif
252
bool write = true;
253
bool read = false;
254
ifaces[iface]->select(read, write, &txmsg, 0);
255
if (!write) {
256
// if there is no space then we need to start from the
257
// top of the queue, so wait for the next loop
258
if (!iface_down) {
259
break;
260
} else {
261
txf->iface_mask &= ~(1U<<iface);
262
}
263
} else if ((txf->iface_mask & (1U<<iface)) && (AP_HAL::micros64() < txf->deadline_usec)) {
264
// try sending to interfaces, clearing the mask if we succeed
265
if (ifaces[iface]->send(txmsg, txf->deadline_usec, 0) > 0) {
266
txf->iface_mask &= ~(1U<<iface);
267
} else {
268
// if we fail to send then we try sending on next interface
269
if (!iface_down) {
270
break;
271
} else {
272
txf->iface_mask &= ~(1U<<iface);
273
}
274
}
275
}
276
// look at next transfer
277
txq = txq->next;
278
if (txq == nullptr) {
279
break;
280
}
281
}
282
}
283
284
}
285
286
void CanardInterface::update_rx_protocol_stats(int16_t res)
287
{
288
switch (res) {
289
case CANARD_OK:
290
protocol_stats.rx_frames++;
291
break;
292
case -CANARD_ERROR_OUT_OF_MEMORY:
293
protocol_stats.rx_error_oom++;
294
break;
295
case -CANARD_ERROR_INTERNAL:
296
protocol_stats.rx_error_internal++;
297
break;
298
case -CANARD_ERROR_RX_INCOMPATIBLE_PACKET:
299
protocol_stats.rx_ignored_not_wanted++;
300
break;
301
case -CANARD_ERROR_RX_WRONG_ADDRESS:
302
protocol_stats.rx_ignored_wrong_address++;
303
break;
304
case -CANARD_ERROR_RX_NOT_WANTED:
305
protocol_stats.rx_ignored_not_wanted++;
306
break;
307
case -CANARD_ERROR_RX_MISSED_START:
308
protocol_stats.rx_error_missed_start++;
309
break;
310
case -CANARD_ERROR_RX_WRONG_TOGGLE:
311
protocol_stats.rx_error_wrong_toggle++;
312
break;
313
case -CANARD_ERROR_RX_UNEXPECTED_TID:
314
protocol_stats.rx_ignored_unexpected_tid++;
315
break;
316
case -CANARD_ERROR_RX_SHORT_FRAME:
317
protocol_stats.rx_error_short_frame++;
318
break;
319
case -CANARD_ERROR_RX_BAD_CRC:
320
protocol_stats.rx_error_bad_crc++;
321
break;
322
default:
323
// mark all other errors as internal
324
protocol_stats.rx_error_internal++;
325
break;
326
}
327
}
328
329
void CanardInterface::processRx() {
330
AP_HAL::CANFrame rxmsg;
331
for (uint8_t i=0; i<num_ifaces; i++) {
332
while(true) {
333
if (ifaces[i] == NULL) {
334
break;
335
}
336
bool read_select = true;
337
bool write_select = false;
338
ifaces[i]->select(read_select, write_select, nullptr, 0);
339
if (!read_select) { // No data pending
340
break;
341
}
342
CanardCANFrame rx_frame {};
343
344
//palToggleLine(HAL_GPIO_PIN_LED);
345
uint64_t timestamp;
346
AP_HAL::CANIface::CanIOFlags flags;
347
if (ifaces[i]->receive(rxmsg, timestamp, flags) <= 0) {
348
break;
349
}
350
351
if (!rxmsg.isExtended()) {
352
// 11 bit frame, see if we have a handler
353
if (aux_11bit_driver != nullptr) {
354
aux_11bit_driver->handle_frame(rxmsg);
355
}
356
continue;
357
}
358
359
rx_frame.data_len = AP_HAL::CANFrame::dlcToDataLength(rxmsg.dlc);
360
memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len);
361
#if HAL_CANFD_SUPPORTED
362
rx_frame.canfd = rxmsg.canfd;
363
#endif
364
rx_frame.id = rxmsg.id;
365
#if CANARD_MULTI_IFACE
366
rx_frame.iface_id = i;
367
#endif
368
{
369
WITH_SEMAPHORE(_sem_rx);
370
371
const int16_t res = canardHandleRxFrame(&canard, &rx_frame, timestamp);
372
if (res == -CANARD_ERROR_RX_MISSED_START) {
373
// this might remaining frames from a message that we don't accept, so check
374
uint64_t dummy_signature;
375
if (shouldAcceptTransfer(&canard,
376
&dummy_signature,
377
extractDataType(rx_frame.id),
378
extractTransferType(rx_frame.id),
379
1)) { // doesn't matter what we pass here
380
update_rx_protocol_stats(res);
381
} else {
382
protocol_stats.rx_ignored_not_wanted++;
383
}
384
} else {
385
update_rx_protocol_stats(res);
386
}
387
}
388
}
389
}
390
}
391
392
void CanardInterface::process(uint32_t duration_ms) {
393
#if AP_TEST_DRONECAN_DRIVERS
394
const uint64_t deadline = AP_HAL::micros64() + duration_ms*1000;
395
while (AP_HAL::micros64() < deadline) {
396
processTestRx();
397
hal.scheduler->delay_microseconds(1000);
398
}
399
#else
400
const uint64_t deadline = AP_HAL::micros64() + duration_ms*1000;
401
while (true) {
402
processRx();
403
processTx();
404
{
405
WITH_SEMAPHORE(_sem_rx);
406
WITH_SEMAPHORE(_sem_tx);
407
canardCleanupStaleTransfers(&canard, AP_HAL::micros64());
408
}
409
const uint64_t now = AP_HAL::micros64();
410
if (now < deadline) {
411
IGNORE_RETURN(sem_handle.wait(deadline - now));
412
} else {
413
break;
414
}
415
}
416
#endif
417
}
418
419
bool CanardInterface::add_interface(AP_HAL::CANIface *can_iface)
420
{
421
if (num_ifaces > HAL_NUM_CAN_IFACES) {
422
AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Num Ifaces Exceeded\n");
423
return false;
424
}
425
if (can_iface == nullptr) {
426
AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Iface Null\n");
427
return false;
428
}
429
if (ifaces[num_ifaces] != nullptr) {
430
AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Iface already added\n");
431
return false;
432
}
433
ifaces[num_ifaces] = can_iface;
434
if (ifaces[num_ifaces] == nullptr) {
435
AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Can't alloc uavcan::iface\n");
436
return false;
437
}
438
if (!can_iface->set_event_handle(&sem_handle)) {
439
AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Setting event handle failed\n");
440
return false;
441
}
442
AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "DroneCANIfaceMgr: Successfully added interface %d\n", int(num_ifaces));
443
num_ifaces++;
444
return true;
445
}
446
447
// add an 11 bit auxillary driver
448
bool CanardInterface::add_11bit_driver(CANSensor *sensor)
449
{
450
if (aux_11bit_driver != nullptr) {
451
// only allow one
452
return false;
453
}
454
aux_11bit_driver = sensor;
455
return true;
456
}
457
458
// handler for outgoing frames for auxillary drivers
459
bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)
460
{
461
const uint64_t tx_deadline_us = AP_HAL::micros64() + timeout_us;
462
bool ret = false;
463
for (uint8_t iface = 0; iface < num_ifaces; iface++) {
464
if (ifaces[iface] == NULL) {
465
continue;
466
}
467
ret |= ifaces[iface]->send(out_frame, tx_deadline_us, 0) > 0;
468
}
469
return ret;
470
}
471
472
#endif // #if HAL_ENABLE_DRONECAN_DRIVERS
473
474