Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_CANManager/AP_CANManager.cpp
9317 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
* 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);
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);
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 AP_PICCOLOCAN_ENABLED
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
251
_drivers[drv_num]->init(drv_num);
252
}
253
254
#if AP_CAN_LOGGING_ENABLED
255
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_CANManager::check_logging_enable, void));
256
#endif
257
}
258
#else
259
void AP_CANManager::init()
260
{
261
WITH_SEMAPHORE(_sem);
262
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
263
if ((AP_CAN::Protocol) _drv_param[i]._driver_type.get() == AP_CAN::Protocol::DroneCAN) {
264
_drivers[i] = _drv_param[i]._uavcan = NEW_NOTHROW AP_DroneCAN(i);
265
266
if (_drivers[i] == nullptr) {
267
AP_BoardConfig::allocation_error("uavcan %d", i + 1);
268
continue;
269
}
270
271
AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[i], AP_DroneCAN::var_info);
272
_drivers[i]->init(i);
273
_driver_type_cache[i] = (AP_CAN::Protocol) _drv_param[i]._driver_type.get();
274
}
275
}
276
}
277
#endif
278
279
/*
280
register a new CAN driver
281
*/
282
bool AP_CANManager::register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver)
283
{
284
WITH_SEMAPHORE(_sem);
285
286
// we need to mutate the HAL to install new CAN interfaces
287
AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable();
288
289
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
290
uint8_t drv_num = _interfaces[i]._driver_number;
291
if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {
292
continue;
293
}
294
// from 1 based to 0 based
295
drv_num--;
296
297
if (dtype != (AP_CAN::Protocol)_drv_param[drv_num]._driver_type.get()) {
298
continue;
299
}
300
if (_drivers[drv_num] != nullptr) {
301
continue;
302
}
303
if (_num_drivers >= HAL_MAX_CAN_PROTOCOL_DRIVERS) {
304
continue;
305
}
306
307
if (hal_mutable.can[i] == nullptr) {
308
// if this interface is not allocated allocate it here,
309
// also pass the index of the CANBus
310
hal_mutable.can[i] = NEW_NOTHROW HAL_CANIface(i);
311
}
312
313
// Initialise the interface we just allocated
314
if (hal_mutable.can[i] == nullptr) {
315
continue;
316
}
317
AP_HAL::CANIface* iface = hal_mutable.can[i];
318
319
_drivers[drv_num] = driver;
320
_drivers[drv_num]->add_interface(iface);
321
log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Adding Interface %d to Driver %d", i + 1, drv_num + 1);
322
323
_drivers[drv_num]->init(drv_num);
324
_driver_type_cache[drv_num] = dtype;
325
326
_num_drivers++;
327
328
return true;
329
}
330
return false;
331
}
332
333
// register a new auxillary sensor driver for 11 bit address frames
334
bool AP_CANManager::register_11bit_driver(AP_CAN::Protocol dtype, CANSensor *sensor, uint8_t &driver_index)
335
{
336
WITH_SEMAPHORE(_sem);
337
338
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
339
uint8_t drv_num = _interfaces[i]._driver_number;
340
if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {
341
continue;
342
}
343
// from 1 based to 0 based
344
drv_num--;
345
346
if (dtype != (AP_CAN::Protocol)_drv_param[drv_num]._driver_type_11bit.get()) {
347
continue;
348
}
349
if (_drivers[drv_num] != nullptr &&
350
_drivers[drv_num]->add_11bit_driver(sensor)) {
351
driver_index = drv_num;
352
return true;
353
}
354
}
355
return false;
356
357
}
358
359
// Method used by CAN related library methods to report status and debug info
360
// The result of this method can be accessed via ftp get @SYS/can_log.txt
361
void AP_CANManager::log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...)
362
{
363
if (_log_buf == nullptr) {
364
return;
365
}
366
if (loglevel > _loglevel) {
367
return;
368
}
369
WITH_SEMAPHORE(_sem);
370
371
if ((LOG_BUFFER_SIZE - _log_pos) < (10 + strlen(tag) + strlen(fmt))) {
372
// reset log pos
373
_log_pos = 0;
374
}
375
//Tag Log Message
376
const char *log_level_tag = "";
377
switch (loglevel) {
378
case AP_CANManager::LOG_DEBUG :
379
log_level_tag = "DEBUG";
380
break;
381
382
case AP_CANManager::LOG_INFO :
383
log_level_tag = "INFO";
384
break;
385
386
case AP_CANManager::LOG_WARNING :
387
log_level_tag = "WARN";
388
break;
389
390
case AP_CANManager::LOG_ERROR :
391
log_level_tag = "ERROR";
392
break;
393
394
case AP_CANManager::LOG_NONE:
395
return;
396
}
397
398
_log_pos += hal.util->snprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, "\n%s %s :", log_level_tag, tag);
399
400
va_list arg_list;
401
va_start(arg_list, fmt);
402
_log_pos += hal.util->vsnprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, fmt, arg_list);
403
va_end(arg_list);
404
}
405
406
// log retrieve method used by file sys method to report can log
407
void AP_CANManager::log_retrieve(ExpandingString &str) const
408
{
409
if (_log_buf == nullptr) {
410
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Log buffer not available");
411
return;
412
}
413
str.append(_log_buf, _log_pos);
414
}
415
416
#if AP_CAN_LOGGING_ENABLED
417
/*
418
handler for CAN frames for frame logging
419
*/
420
void AP_CANManager::can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags)
421
{
422
#if HAL_CANFD_SUPPORTED
423
if (frame.canfd) {
424
struct log_CAFD pkt {
425
LOG_PACKET_HEADER_INIT(LOG_CAFD_MSG),
426
time_us : AP_HAL::micros64(),
427
bus : bus,
428
id : frame.id,
429
dlc : frame.dlc
430
};
431
memcpy(pkt.data, frame.data, frame.dlcToDataLength(frame.dlc));
432
AP::logger().WriteBlock(&pkt, sizeof(pkt));
433
return;
434
}
435
#endif
436
struct log_CANF pkt {
437
LOG_PACKET_HEADER_INIT(LOG_CANF_MSG),
438
time_us : AP_HAL::micros64(),
439
bus : bus,
440
id : frame.id,
441
dlc : frame.dlc
442
};
443
memcpy(pkt.data, frame.data, frame.dlc);
444
AP::logger().WriteBlock(&pkt, sizeof(pkt));
445
}
446
447
/*
448
see if we need to enable/disable the CAN logging callback
449
*/
450
void AP_CANManager::check_logging_enable(void)
451
{
452
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
453
const bool enabled = _interfaces[i].option_is_set(CANIface_Params::Options::LOG_ALL_FRAMES);
454
uint8_t &logging_id = _interfaces[i].logging_id;
455
auto *can = hal.can[i];
456
if (can == nullptr) {
457
continue;
458
}
459
if (enabled && logging_id == 0) {
460
can->register_frame_callback(
461
FUNCTOR_BIND_MEMBER(&AP_CANManager::can_logging_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags),
462
logging_id);
463
} else if (!enabled && logging_id != 0) {
464
can->unregister_frame_callback(logging_id);
465
}
466
}
467
}
468
469
#endif // AP_CAN_LOGGING_ENABLED
470
471
AP_CANManager& AP::can()
472
{
473
return *AP_CANManager::get_singleton();
474
}
475
476
#endif
477
478
479