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_CANManager/AP_CANManager.cpp
Views: 1798
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
* AP_CANManager - board specific configuration for CAN interface
17
*/
18
19
#include <AP_HAL/AP_HAL.h>
20
#include <AP_Common/AP_Common.h>
21
#include "AP_CANManager.h"
22
23
#if HAL_CANMANAGER_ENABLED
24
25
#include <AP_BoardConfig/AP_BoardConfig.h>
26
#include <AP_Vehicle/AP_Vehicle_Type.h>
27
#include <AP_DroneCAN/AP_DroneCAN.h>
28
#include <AP_KDECAN/AP_KDECAN.h>
29
#include <AP_SerialManager/AP_SerialManager.h>
30
#include <AP_PiccoloCAN/AP_PiccoloCAN.h>
31
#include <AP_EFI/AP_EFI_NWPMU.h>
32
#include <GCS_MAVLink/GCS.h>
33
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
34
#include <AP_HAL_Linux/CANSocketIface.h>
35
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
36
#include <AP_HAL_SITL/CANSocketIface.h>
37
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
38
#include <hal.h>
39
#include <AP_HAL_ChibiOS/CANIface.h>
40
#endif
41
42
#include <AP_Common/ExpandingString.h>
43
#include <AP_Common/sorting.h>
44
#include <AP_Logger/AP_Logger.h>
45
46
#define LOG_TAG "CANMGR"
47
#define LOG_BUFFER_SIZE 1024
48
49
extern const AP_HAL::HAL& hal;
50
51
// table of user settable parameters
52
const AP_Param::GroupInfo AP_CANManager::var_info[] = {
53
54
#if HAL_NUM_CAN_IFACES > 0
55
// @Group: P1_
56
// @Path: ../AP_CANManager/AP_CANIfaceParams.cpp
57
AP_SUBGROUPINFO(_interfaces[0], "P1_", 1, AP_CANManager, AP_CANManager::CANIface_Params),
58
#endif
59
60
#if HAL_NUM_CAN_IFACES > 1
61
// @Group: P2_
62
// @Path: ../AP_CANManager/AP_CANIfaceParams.cpp
63
AP_SUBGROUPINFO(_interfaces[1], "P2_", 2, AP_CANManager, AP_CANManager::CANIface_Params),
64
#endif
65
66
#if HAL_NUM_CAN_IFACES > 2
67
// @Group: P3_
68
// @Path: ../AP_CANManager/AP_CANIfaceParams.cpp
69
AP_SUBGROUPINFO(_interfaces[2], "P3_", 3, AP_CANManager, AP_CANManager::CANIface_Params),
70
#endif
71
72
#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 0
73
// @Group: D1_
74
// @Path: ../AP_CANManager/AP_CANManager_CANDriver_Params.cpp
75
AP_SUBGROUPINFO(_drv_param[0], "D1_", 4, AP_CANManager, AP_CANManager::CANDriver_Params),
76
#endif
77
78
#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1
79
// @Group: D2_
80
// @Path: ../AP_CANManager/AP_CANManager_CANDriver_Params.cpp
81
AP_SUBGROUPINFO(_drv_param[1], "D2_", 5, AP_CANManager, AP_CANManager::CANDriver_Params),
82
#endif
83
84
#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 2
85
// @Group: D3_
86
// @Path: ../AP_CANManager/AP_CANManager_CANDriver_Params.cpp
87
AP_SUBGROUPINFO(_drv_param[2], "D3_", 6, AP_CANManager, AP_CANManager::CANDriver_Params),
88
#endif
89
90
#if AP_CAN_SLCAN_ENABLED
91
// @Group: SLCAN_
92
// @Path: ../AP_CANManager/AP_SLCANIface.cpp
93
AP_SUBGROUPINFO(_slcan_interface, "SLCAN_", 7, AP_CANManager, SLCAN::CANIface),
94
#endif
95
96
// @Param: LOGLEVEL
97
// @DisplayName: Loglevel
98
// @Description: Loglevel for recording initialisation and debug information from CAN Interface
99
// @Range: 0 4
100
// @Values: 0: Log None, 1: Log Error, 2: Log Warning and below, 3: Log Info and below, 4: Log Everything
101
// @User: Advanced
102
AP_GROUPINFO("LOGLEVEL", 8, AP_CANManager, _loglevel, AP_CANManager::LOG_NONE),
103
104
AP_GROUPEND
105
};
106
107
AP_CANManager *AP_CANManager::_singleton;
108
109
AP_CANManager::AP_CANManager()
110
{
111
AP_Param::setup_object_defaults(this, var_info);
112
if (_singleton != nullptr) {
113
AP_HAL::panic("AP_CANManager must be singleton");
114
}
115
_singleton = this;
116
}
117
118
#if !AP_TEST_DRONECAN_DRIVERS
119
void AP_CANManager::init()
120
{
121
WITH_SEMAPHORE(_sem);
122
123
// we need to mutate the HAL to install new CAN interfaces
124
AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable();
125
126
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
127
if (AP::sitl() == nullptr) {
128
AP_HAL::panic("CANManager: SITL not initialised!");
129
}
130
#endif
131
// We only allocate log buffer only when under debug
132
if (_loglevel != AP_CANManager::LOG_NONE) {
133
_log_buf = NEW_NOTHROW char[LOG_BUFFER_SIZE];
134
_log_pos = 0;
135
}
136
137
#if AP_CAN_SLCAN_ENABLED
138
//Reset all SLCAN related params that needs resetting at boot
139
_slcan_interface.reset_params();
140
#endif
141
142
AP_CAN::Protocol drv_type[HAL_MAX_CAN_PROTOCOL_DRIVERS] = {};
143
// loop through interfaces and allocate and initialise Iface,
144
// Also allocate Driver objects, and add interfaces to them
145
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
146
// Get associated Driver to the interface
147
uint8_t drv_num = _interfaces[i]._driver_number;
148
if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {
149
continue;
150
}
151
drv_num--;
152
153
if (hal_mutable.can[i] == nullptr) {
154
// So if this interface is not allocated allocate it here,
155
// also pass the index of the CANBus
156
hal_mutable.can[i] = NEW_NOTHROW HAL_CANIface(i);
157
}
158
159
// Initialise the interface we just allocated
160
if (hal_mutable.can[i] == nullptr) {
161
continue;
162
}
163
AP_HAL::CANIface* iface = hal_mutable.can[i];
164
165
// Find the driver type that we need to allocate and register this interface with
166
drv_type[drv_num] = (AP_CAN::Protocol) _drv_param[drv_num]._driver_type.get();
167
bool can_initialised = false;
168
// Check if this interface need hooking up to slcan passthrough
169
// instead of a driver
170
#if AP_CAN_SLCAN_ENABLED
171
if (_slcan_interface.init_passthrough(i)) {
172
// we have slcan bridge setup pass that on as can iface
173
can_initialised = hal_mutable.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode);
174
iface = &_slcan_interface;
175
} else {
176
#else
177
if (true) {
178
#endif
179
can_initialised = hal_mutable.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode);
180
}
181
182
if (!can_initialised) {
183
log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "Failed to initialise CAN Interface %d", i+1);
184
continue;
185
}
186
187
log_text(AP_CANManager::LOG_INFO, LOG_TAG, "CAN Interface %d initialized well", i + 1);
188
189
if (_drivers[drv_num] != nullptr) {
190
//We already initialised the driver just add interface and move on
191
log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Adding Interface %d to Driver %d", i + 1, drv_num + 1);
192
_drivers[drv_num]->add_interface(iface);
193
continue;
194
}
195
196
if (_num_drivers >= HAL_MAX_CAN_PROTOCOL_DRIVERS) {
197
// We are exceeding number of drivers,
198
// this can't be happening time to panic
199
AP_BoardConfig::config_error("Max number of CAN Drivers exceeded\n\r");
200
}
201
202
// Allocate the set type of Driver
203
switch (drv_type[drv_num]) {
204
#if HAL_ENABLE_DRONECAN_DRIVERS
205
case AP_CAN::Protocol::DroneCAN:
206
_drivers[drv_num] = _drv_param[drv_num]._uavcan = NEW_NOTHROW AP_DroneCAN(drv_num);
207
208
if (_drivers[drv_num] == nullptr) {
209
AP_BoardConfig::allocation_error("uavcan %d", i + 1);
210
continue;
211
}
212
213
AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[drv_num], AP_DroneCAN::var_info);
214
break;
215
#endif
216
#if HAL_PICCOLO_CAN_ENABLE
217
case AP_CAN::Protocol::PiccoloCAN:
218
_drivers[drv_num] = _drv_param[drv_num]._piccolocan = NEW_NOTHROW AP_PiccoloCAN;
219
220
if (_drivers[drv_num] == nullptr) {
221
AP_BoardConfig::allocation_error("PiccoloCAN %d", drv_num + 1);
222
continue;
223
}
224
225
AP_Param::load_object_from_eeprom((AP_PiccoloCAN*)_drivers[drv_num], AP_PiccoloCAN::var_info);
226
break;
227
#endif
228
default:
229
continue;
230
}
231
232
_num_drivers++;
233
234
// Hook this interface to the selected Driver Type
235
_drivers[drv_num]->add_interface(iface);
236
log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Adding Interface %d to Driver %d", i + 1, drv_num + 1);
237
238
}
239
240
for (uint8_t drv_num = 0; drv_num < HAL_MAX_CAN_PROTOCOL_DRIVERS; drv_num++) {
241
//initialise all the Drivers
242
243
// Cache the driver type, initialized or not, so we can detect that it is in the params at boot via get_driver_type().
244
// This allows drivers that are initialized by CANSensor instead of CANManager to know if they should init or not
245
_driver_type_cache[drv_num] = drv_type[drv_num];
246
247
if (_drivers[drv_num] == nullptr) {
248
continue;
249
}
250
bool enable_filter = false;
251
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
252
if (_interfaces[i]._driver_number == (drv_num+1) &&
253
hal_mutable.can[i] != nullptr &&
254
hal_mutable.can[i]->get_operating_mode() == AP_HAL::CANIface::FilteredMode) {
255
// Don't worry we don't enable Filters for Normal Ifaces under the driver
256
// this is just to ensure we enable them for the ones we already decided on
257
enable_filter = true;
258
break;
259
}
260
}
261
262
_drivers[drv_num]->init(drv_num, enable_filter);
263
}
264
265
#if AP_CAN_LOGGING_ENABLED
266
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_CANManager::check_logging_enable, void));
267
#endif
268
}
269
#else
270
void AP_CANManager::init()
271
{
272
WITH_SEMAPHORE(_sem);
273
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
274
if ((AP_CAN::Protocol) _drv_param[i]._driver_type.get() == AP_CAN::Protocol::DroneCAN) {
275
_drivers[i] = _drv_param[i]._uavcan = NEW_NOTHROW AP_DroneCAN(i);
276
277
if (_drivers[i] == nullptr) {
278
AP_BoardConfig::allocation_error("uavcan %d", i + 1);
279
continue;
280
}
281
282
AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[i], AP_DroneCAN::var_info);
283
_drivers[i]->init(i, true);
284
_driver_type_cache[i] = (AP_CAN::Protocol) _drv_param[i]._driver_type.get();
285
}
286
}
287
}
288
#endif
289
290
/*
291
register a new CAN driver
292
*/
293
bool AP_CANManager::register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver)
294
{
295
WITH_SEMAPHORE(_sem);
296
297
// we need to mutate the HAL to install new CAN interfaces
298
AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable();
299
300
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
301
uint8_t drv_num = _interfaces[i]._driver_number;
302
if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {
303
continue;
304
}
305
// from 1 based to 0 based
306
drv_num--;
307
308
if (dtype != (AP_CAN::Protocol)_drv_param[drv_num]._driver_type.get()) {
309
continue;
310
}
311
if (_drivers[drv_num] != nullptr) {
312
continue;
313
}
314
if (_num_drivers >= HAL_MAX_CAN_PROTOCOL_DRIVERS) {
315
continue;
316
}
317
318
if (hal_mutable.can[i] == nullptr) {
319
// if this interface is not allocated allocate it here,
320
// also pass the index of the CANBus
321
hal_mutable.can[i] = NEW_NOTHROW HAL_CANIface(i);
322
}
323
324
// Initialise the interface we just allocated
325
if (hal_mutable.can[i] == nullptr) {
326
continue;
327
}
328
AP_HAL::CANIface* iface = hal_mutable.can[i];
329
330
_drivers[drv_num] = driver;
331
_drivers[drv_num]->add_interface(iface);
332
log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Adding Interface %d to Driver %d", i + 1, drv_num + 1);
333
334
_drivers[drv_num]->init(drv_num, false);
335
_driver_type_cache[drv_num] = dtype;
336
337
_num_drivers++;
338
339
return true;
340
}
341
return false;
342
}
343
344
// register a new auxillary sensor driver for 11 bit address frames
345
bool AP_CANManager::register_11bit_driver(AP_CAN::Protocol dtype, CANSensor *sensor, uint8_t &driver_index)
346
{
347
WITH_SEMAPHORE(_sem);
348
349
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
350
uint8_t drv_num = _interfaces[i]._driver_number;
351
if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {
352
continue;
353
}
354
// from 1 based to 0 based
355
drv_num--;
356
357
if (dtype != (AP_CAN::Protocol)_drv_param[drv_num]._driver_type_11bit.get()) {
358
continue;
359
}
360
if (_drivers[drv_num] != nullptr &&
361
_drivers[drv_num]->add_11bit_driver(sensor)) {
362
driver_index = drv_num;
363
return true;
364
}
365
}
366
return false;
367
368
}
369
370
// Method used by CAN related library methods to report status and debug info
371
// The result of this method can be accessed via ftp get @SYS/can_log.txt
372
void AP_CANManager::log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...)
373
{
374
if (_log_buf == nullptr) {
375
return;
376
}
377
if (loglevel > _loglevel) {
378
return;
379
}
380
WITH_SEMAPHORE(_sem);
381
382
if ((LOG_BUFFER_SIZE - _log_pos) < (10 + strlen(tag) + strlen(fmt))) {
383
// reset log pos
384
_log_pos = 0;
385
}
386
//Tag Log Message
387
const char *log_level_tag = "";
388
switch (loglevel) {
389
case AP_CANManager::LOG_DEBUG :
390
log_level_tag = "DEBUG";
391
break;
392
393
case AP_CANManager::LOG_INFO :
394
log_level_tag = "INFO";
395
break;
396
397
case AP_CANManager::LOG_WARNING :
398
log_level_tag = "WARN";
399
break;
400
401
case AP_CANManager::LOG_ERROR :
402
log_level_tag = "ERROR";
403
break;
404
405
case AP_CANManager::LOG_NONE:
406
return;
407
}
408
409
_log_pos += hal.util->snprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, "\n%s %s :", log_level_tag, tag);
410
411
va_list arg_list;
412
va_start(arg_list, fmt);
413
_log_pos += hal.util->vsnprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, fmt, arg_list);
414
va_end(arg_list);
415
}
416
417
// log retrieve method used by file sys method to report can log
418
void AP_CANManager::log_retrieve(ExpandingString &str) const
419
{
420
if (_log_buf == nullptr) {
421
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Log buffer not available");
422
return;
423
}
424
str.append(_log_buf, _log_pos);
425
}
426
427
#if HAL_GCS_ENABLED
428
/*
429
handle MAV_CMD_CAN_FORWARD mavlink long command
430
*/
431
bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg)
432
{
433
WITH_SEMAPHORE(can_forward.sem);
434
const int8_t bus = int8_t(packet.param1)-1;
435
436
if (bus == -1) {
437
/*
438
a request to stop forwarding
439
*/
440
if (can_forward.callback_id != 0) {
441
hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);
442
can_forward.callback_id = 0;
443
}
444
return true;
445
}
446
447
if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {
448
return false;
449
}
450
451
if (can_forward.callback_id != 0 && can_forward.callback_bus != bus) {
452
/*
453
the client is changing which bus they are monitoring, unregister from the previous bus
454
*/
455
hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);
456
can_forward.callback_id = 0;
457
}
458
459
if (can_forward.callback_id == 0 &&
460
!hal.can[bus]->register_frame_callback(
461
FUNCTOR_BIND_MEMBER(&AP_CANManager::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &), can_forward.callback_id)) {
462
// failed to register the callback
463
return false;
464
}
465
466
can_forward.callback_bus = bus;
467
can_forward.last_callback_enable_ms = AP_HAL::millis();
468
can_forward.chan = chan;
469
can_forward.system_id = msg.sysid;
470
can_forward.component_id = msg.compid;
471
472
return true;
473
}
474
475
/*
476
handle a CAN_FRAME packet
477
*/
478
void AP_CANManager::handle_can_frame(const mavlink_message_t &msg)
479
{
480
if (frame_buffer == nullptr) {
481
// allocate frame buffer
482
WITH_SEMAPHORE(_sem);
483
// 20 is good for firmware upload
484
uint8_t buffer_size = 20;
485
while (frame_buffer == nullptr && buffer_size > 0) {
486
// we'd like 20 frames, but will live with less
487
frame_buffer = NEW_NOTHROW ObjectBuffer<BufferFrame>(buffer_size);
488
if (frame_buffer != nullptr && frame_buffer->get_size() != 0) {
489
// register a callback for when frames can't be sent immediately
490
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_CANManager::process_frame_buffer, void));
491
break;
492
}
493
delete frame_buffer;
494
frame_buffer = nullptr;
495
buffer_size /= 2;
496
}
497
if (frame_buffer == nullptr) {
498
// discard the frames
499
return;
500
}
501
}
502
503
switch (msg.msgid) {
504
case MAVLINK_MSG_ID_CAN_FRAME: {
505
mavlink_can_frame_t p;
506
mavlink_msg_can_frame_decode(&msg, &p);
507
if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {
508
return;
509
}
510
struct BufferFrame frame {
511
bus : p.bus,
512
frame : AP_HAL::CANFrame(p.id, p.data, p.len)
513
};
514
WITH_SEMAPHORE(_sem);
515
frame_buffer->push(frame);
516
break;
517
}
518
#if HAL_CANFD_SUPPORTED
519
case MAVLINK_MSG_ID_CANFD_FRAME: {
520
mavlink_canfd_frame_t p;
521
mavlink_msg_canfd_frame_decode(&msg, &p);
522
if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {
523
return;
524
}
525
struct BufferFrame frame {
526
bus : p.bus,
527
frame : AP_HAL::CANFrame(p.id, p.data, p.len, true)
528
};
529
WITH_SEMAPHORE(_sem);
530
frame_buffer->push(frame);
531
break;
532
}
533
#endif
534
}
535
process_frame_buffer();
536
}
537
538
/*
539
process the frame buffer
540
*/
541
void AP_CANManager::process_frame_buffer(void)
542
{
543
while (frame_buffer) {
544
WITH_SEMAPHORE(_sem);
545
struct BufferFrame frame;
546
const uint16_t timeout_us = 2000;
547
if (!frame_buffer->peek(frame)) {
548
// no frames in the queue
549
break;
550
}
551
const int16_t retcode = hal.can[frame.bus]->send(frame.frame,
552
AP_HAL::micros64() + timeout_us,
553
AP_HAL::CANIface::IsMAVCAN);
554
if (retcode == 0) {
555
// no space in the CAN output slots, try again later
556
break;
557
}
558
// retcode == 1 means sent, -1 means a frame that can't be
559
// sent. Either way we should remove from the queue
560
frame_buffer->pop();
561
}
562
}
563
564
/*
565
handle a CAN_FILTER_MODIFY packet
566
*/
567
void AP_CANManager::handle_can_filter_modify(const mavlink_message_t &msg)
568
{
569
mavlink_can_filter_modify_t p;
570
mavlink_msg_can_filter_modify_decode(&msg, &p);
571
const int8_t bus = int8_t(p.bus)-1;
572
if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {
573
return;
574
}
575
if (p.num_ids > ARRAY_SIZE(p.ids)) {
576
return;
577
}
578
uint16_t *new_ids = nullptr;
579
uint16_t num_new_ids = 0;
580
WITH_SEMAPHORE(can_forward.sem);
581
582
// sort the list, so we can bisection search and the array
583
// operations below are efficient
584
insertion_sort_uint16(p.ids, p.num_ids);
585
586
switch (p.operation) {
587
case CAN_FILTER_REPLACE: {
588
if (p.num_ids == 0) {
589
can_forward.num_filter_ids = 0;
590
delete[] can_forward.filter_ids;
591
can_forward.filter_ids = nullptr;
592
return;
593
}
594
if (p.num_ids == can_forward.num_filter_ids &&
595
memcmp(p.ids, can_forward.filter_ids, p.num_ids*sizeof(uint16_t)) == 0) {
596
// common case of replacing with identical list
597
return;
598
}
599
new_ids = NEW_NOTHROW uint16_t[p.num_ids];
600
if (new_ids != nullptr) {
601
num_new_ids = p.num_ids;
602
memcpy((void*)new_ids, (const void *)p.ids, p.num_ids*sizeof(uint16_t));
603
}
604
break;
605
}
606
case CAN_FILTER_ADD: {
607
if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,
608
p.ids, p.num_ids) == p.num_ids) {
609
// nothing changing
610
return;
611
}
612
new_ids = NEW_NOTHROW uint16_t[can_forward.num_filter_ids+p.num_ids];
613
if (new_ids == nullptr) {
614
return;
615
}
616
if (can_forward.num_filter_ids != 0) {
617
memcpy(new_ids, can_forward.filter_ids, can_forward.num_filter_ids*sizeof(uint16_t));
618
}
619
memcpy(&new_ids[can_forward.num_filter_ids], p.ids, p.num_ids*sizeof(uint16_t));
620
insertion_sort_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);
621
num_new_ids = remove_duplicates_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);
622
break;
623
}
624
case CAN_FILTER_REMOVE: {
625
if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,
626
p.ids, p.num_ids) == 0) {
627
// nothing changing
628
return;
629
}
630
can_forward.num_filter_ids = remove_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,
631
p.ids, p.num_ids);
632
if (can_forward.num_filter_ids == 0) {
633
delete[] can_forward.filter_ids;
634
can_forward.filter_ids = nullptr;
635
}
636
break;
637
}
638
}
639
if (new_ids != nullptr) {
640
// handle common case of no change
641
if (num_new_ids == can_forward.num_filter_ids &&
642
memcmp(new_ids, can_forward.filter_ids, num_new_ids*sizeof(uint16_t)) == 0) {
643
delete[] new_ids;
644
} else {
645
// put the new list in place
646
delete[] can_forward.filter_ids;
647
can_forward.filter_ids = new_ids;
648
can_forward.num_filter_ids = num_new_ids;
649
}
650
}
651
}
652
653
/*
654
handler for CAN frames from the registered callback, sending frames
655
out as CAN_FRAME or CANFD_FRAME messages
656
*/
657
void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame)
658
{
659
WITH_SEMAPHORE(can_forward.sem);
660
if (bus != can_forward.callback_bus) {
661
// we are not registered for forwarding this bus, discard frame
662
return;
663
}
664
if (can_forward.frame_counter++ == 100) {
665
// check every 100 frames for disabling CAN_FRAME send
666
// we stop sending after 5s if the client stops
667
// sending MAV_CMD_CAN_FORWARD requests
668
if (can_forward.callback_id != 0 &&
669
AP_HAL::millis() - can_forward.last_callback_enable_ms > 5000) {
670
hal.can[bus]->unregister_frame_callback(can_forward.callback_id);
671
can_forward.callback_id = 0;
672
return;
673
}
674
can_forward.frame_counter = 0;
675
}
676
WITH_SEMAPHORE(comm_chan_lock(can_forward.chan));
677
if (can_forward.filter_ids != nullptr) {
678
// work out ID of this frame
679
uint16_t id = 0;
680
if ((frame.id&0xff) != 0) {
681
// not anonymous
682
if (frame.id & 0x80) {
683
// service message
684
id = uint8_t(frame.id>>16);
685
} else {
686
// message frame
687
id = uint16_t(frame.id>>8);
688
}
689
}
690
if (!bisect_search_uint16(can_forward.filter_ids, can_forward.num_filter_ids, id)) {
691
return;
692
}
693
}
694
const uint8_t data_len = AP_HAL::CANFrame::dlcToDataLength(frame.dlc);
695
#if HAL_CANFD_SUPPORTED
696
if (frame.isCanFDFrame()) {
697
if (HAVE_PAYLOAD_SPACE(can_forward.chan, CANFD_FRAME)) {
698
mavlink_msg_canfd_frame_send(can_forward.chan, can_forward.system_id, can_forward.component_id,
699
bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));
700
}
701
} else
702
#endif
703
{
704
if (HAVE_PAYLOAD_SPACE(can_forward.chan, CAN_FRAME)) {
705
mavlink_msg_can_frame_send(can_forward.chan, can_forward.system_id, can_forward.component_id,
706
bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));
707
}
708
}
709
}
710
#endif // HAL_GCS_ENABLED
711
712
#if AP_CAN_LOGGING_ENABLED
713
/*
714
handler for CAN frames for frame logging
715
*/
716
void AP_CANManager::can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame)
717
{
718
#if HAL_CANFD_SUPPORTED
719
if (frame.canfd) {
720
struct log_CAFD pkt {
721
LOG_PACKET_HEADER_INIT(LOG_CAFD_MSG),
722
time_us : AP_HAL::micros64(),
723
bus : bus,
724
id : frame.id,
725
dlc : frame.dlc
726
};
727
memcpy(pkt.data, frame.data, frame.dlcToDataLength(frame.dlc));
728
AP::logger().WriteBlock(&pkt, sizeof(pkt));
729
return;
730
}
731
#endif
732
struct log_CANF pkt {
733
LOG_PACKET_HEADER_INIT(LOG_CANF_MSG),
734
time_us : AP_HAL::micros64(),
735
bus : bus,
736
id : frame.id,
737
dlc : frame.dlc
738
};
739
memcpy(pkt.data, frame.data, frame.dlc);
740
AP::logger().WriteBlock(&pkt, sizeof(pkt));
741
}
742
743
/*
744
see if we need to enable/disable the CAN logging callback
745
*/
746
void AP_CANManager::check_logging_enable(void)
747
{
748
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
749
const bool enabled = _interfaces[i].option_is_set(CANIface_Params::Options::LOG_ALL_FRAMES);
750
uint8_t &logging_id = _interfaces[i].logging_id;
751
auto *can = hal.can[i];
752
if (can == nullptr) {
753
continue;
754
}
755
if (enabled && logging_id == 0) {
756
can->register_frame_callback(
757
FUNCTOR_BIND_MEMBER(&AP_CANManager::can_logging_callback, void, uint8_t, const AP_HAL::CANFrame &),
758
logging_id);
759
} else if (!enabled && logging_id != 0) {
760
can->unregister_frame_callback(logging_id);
761
}
762
}
763
}
764
765
#endif // AP_CAN_LOGGING_ENABLED
766
767
AP_CANManager& AP::can()
768
{
769
return *AP_CANManager::get_singleton();
770
}
771
772
#endif
773
774
775