Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_CANManager/AP_SLCANIface.cpp
9451 views
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
* Referenced from implementation by Pavel Kirienko <[email protected]>
17
* for Zubax Babel
18
*/
19
20
#include "AP_SLCANIface.h"
21
22
#if AP_CAN_SLCAN_ENABLED
23
#include <AP_HAL/AP_HAL.h>
24
#include <AP_Common/AP_Common.h>
25
26
#include "AP_CANManager.h"
27
28
#include <AP_SerialManager/AP_SerialManager.h>
29
#include <stdio.h>
30
#include <AP_Vehicle/AP_Vehicle_Type.h>
31
#include <GCS_MAVLink/GCS.h>
32
33
#define LOG_TAG "SLCAN"
34
35
extern const AP_HAL::HAL& hal;
36
37
const AP_Param::GroupInfo SLCAN::CANIface::var_info[] = {
38
// @Param: CPORT
39
// @DisplayName: SLCAN Route
40
// @Description: CAN Interface ID to be routed to SLCAN, 0 means no routing
41
// @Values: 0:Disabled,1:First interface,2:Second interface
42
// @User: Standard
43
// @RebootRequired: True
44
AP_GROUPINFO("CPORT", 1, SLCAN::CANIface, _slcan_can_port, 0),
45
46
// @Param: SERNUM
47
// @DisplayName: SLCAN Serial Port
48
// @Description: Serial Port ID to be used for temporary SLCAN iface, -1 means no temporary serial. This parameter is automatically reset on reboot or on timeout. See CAN_SLCAN_TIMOUT for timeout details
49
// @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6
50
// @User: Standard
51
AP_GROUPINFO("SERNUM", 2, SLCAN::CANIface, _slcan_ser_port, -1),
52
53
// @Param: TIMOUT
54
// @DisplayName: SLCAN Timeout
55
// @Description: Duration of inactivity after which SLCAN is switched back to original driver in seconds.
56
// @Range: 0 127
57
// @User: Standard
58
AP_GROUPINFO("TIMOUT", 3, SLCAN::CANIface, _slcan_timeout, 0),
59
60
// @Param: SDELAY
61
// @DisplayName: SLCAN Start Delay
62
// @Description: Duration after which slcan starts after setting SERNUM in seconds.
63
// @Range: 0 127
64
// @User: Standard
65
AP_GROUPINFO("SDELAY", 4, SLCAN::CANIface, _slcan_start_delay, 1),
66
67
AP_GROUPEND
68
};
69
70
////////Helper Methods//////////
71
72
static bool hex2nibble_error;
73
74
static uint8_t nibble2hex(uint8_t x)
75
{
76
// Allocating in RAM because it's faster
77
static uint8_t ConversionTable[] = {
78
'0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F'
79
};
80
return ConversionTable[x & 0x0F];
81
}
82
83
static uint8_t hex2nibble(char c)
84
{
85
uint8_t out = char_to_hex(c);
86
87
if (out == 255) {
88
hex2nibble_error = true;
89
}
90
return out;
91
}
92
93
bool SLCAN::CANIface::push_Frame(AP_HAL::CANFrame &frame)
94
{
95
AP_HAL::CANIface::CanRxItem frm;
96
frm.frame = frame;
97
frm.flags = 0;
98
frm.timestamp_us = AP_HAL::micros64();
99
return add_to_rx_queue(frm);
100
}
101
102
/**
103
* General frame format:
104
* <type> <id> <dlc> <data>
105
* The emitting functions below are highly optimized for speed.
106
*/
107
bool SLCAN::CANIface::handle_FrameDataExt(const char* cmd, bool canfd)
108
{
109
AP_HAL::CANFrame f {};
110
hex2nibble_error = false;
111
f.canfd = canfd;
112
f.id = f.FlagEFF |
113
(hex2nibble(cmd[1]) << 28) |
114
(hex2nibble(cmd[2]) << 24) |
115
(hex2nibble(cmd[3]) << 20) |
116
(hex2nibble(cmd[4]) << 16) |
117
(hex2nibble(cmd[5]) << 12) |
118
(hex2nibble(cmd[6]) << 8) |
119
(hex2nibble(cmd[7]) << 4) |
120
(hex2nibble(cmd[8]) << 0);
121
f.dlc = hex2nibble(cmd[9]);
122
if (hex2nibble_error || f.dlc > (canfd?15:8)) {
123
return false;
124
}
125
{
126
const char* p = &cmd[10];
127
const uint8_t dlen = AP_HAL::CANFrame::dlcToDataLength(f.dlc);
128
for (unsigned i = 0; i < dlen; i++) {
129
f.data[i] = (hex2nibble(*p) << 4) | hex2nibble(*(p + 1));
130
p += 2;
131
}
132
}
133
if (hex2nibble_error) {
134
return false;
135
}
136
return push_Frame(f);
137
}
138
139
/**
140
* General frame format:
141
* <type> <id> <dlc> <data>
142
* The emitting functions below are highly optimized for speed.
143
*/
144
bool SLCAN::CANIface::handle_FDFrameDataExt(const char* cmd)
145
{
146
#if HAL_CANFD_SUPPORTED
147
return false;
148
#else
149
AP_HAL::CANFrame f {};
150
hex2nibble_error = false;
151
f.canfd = true;
152
f.id = f.FlagEFF |
153
(hex2nibble(cmd[1]) << 28) |
154
(hex2nibble(cmd[2]) << 24) |
155
(hex2nibble(cmd[3]) << 20) |
156
(hex2nibble(cmd[4]) << 16) |
157
(hex2nibble(cmd[5]) << 12) |
158
(hex2nibble(cmd[6]) << 8) |
159
(hex2nibble(cmd[7]) << 4) |
160
(hex2nibble(cmd[8]) << 0);
161
f.dlc = hex2nibble(cmd[9]);
162
if (f.dlc > AP_HAL::CANFrame::dataLengthToDlc(AP_HAL::CANFrame::MaxDataLen)) {
163
return false;
164
}
165
{
166
const char* p = &cmd[10];
167
for (unsigned i = 0; i < AP_HAL::CANFrame::dlcToDataLength(f.dlc); i++) {
168
f.data[i] = (hex2nibble(*p) << 4) | hex2nibble(*(p + 1));
169
p += 2;
170
}
171
}
172
if (hex2nibble_error) {
173
return false;
174
}
175
return push_Frame(f);
176
#endif //#if HAL_CANFD_SUPPORTED
177
}
178
179
bool SLCAN::CANIface::handle_FrameDataStd(const char* cmd)
180
{
181
AP_HAL::CANFrame f {};
182
hex2nibble_error = false;
183
f.id = (hex2nibble(cmd[1]) << 8) |
184
(hex2nibble(cmd[2]) << 4) |
185
(hex2nibble(cmd[3]) << 0);
186
if (cmd[4] < '0' || cmd[4] > ('0' + AP_HAL::CANFrame::NonFDCANMaxDataLen)) {
187
return false;
188
}
189
f.dlc = cmd[4] - '0';
190
if (f.dlc > AP_HAL::CANFrame::NonFDCANMaxDataLen) {
191
return false;
192
}
193
{
194
const char* p = &cmd[5];
195
for (unsigned i = 0; i < f.dlc; i++) {
196
f.data[i] = (hex2nibble(*p) << 4) | hex2nibble(*(p + 1));
197
p += 2;
198
}
199
}
200
if (hex2nibble_error) {
201
return false;
202
}
203
return push_Frame(f);
204
}
205
206
bool SLCAN::CANIface::handle_FrameRTRExt(const char* cmd)
207
{
208
AP_HAL::CANFrame f {};
209
hex2nibble_error = false;
210
f.id = f.FlagEFF | f.FlagRTR |
211
(hex2nibble(cmd[1]) << 28) |
212
(hex2nibble(cmd[2]) << 24) |
213
(hex2nibble(cmd[3]) << 20) |
214
(hex2nibble(cmd[4]) << 16) |
215
(hex2nibble(cmd[5]) << 12) |
216
(hex2nibble(cmd[6]) << 8) |
217
(hex2nibble(cmd[7]) << 4) |
218
(hex2nibble(cmd[8]) << 0);
219
if (cmd[9] < '0' || cmd[9] > ('0' + AP_HAL::CANFrame::NonFDCANMaxDataLen)) {
220
return false;
221
}
222
f.dlc = cmd[9] - '0';
223
224
if (f.dlc > AP_HAL::CANFrame::NonFDCANMaxDataLen) {
225
return false;
226
}
227
if (hex2nibble_error) {
228
return false;
229
}
230
return push_Frame(f);
231
}
232
233
bool SLCAN::CANIface::handle_FrameRTRStd(const char* cmd)
234
{
235
AP_HAL::CANFrame f {};
236
hex2nibble_error = false;
237
f.id = f.FlagRTR |
238
(hex2nibble(cmd[1]) << 8) |
239
(hex2nibble(cmd[2]) << 4) |
240
(hex2nibble(cmd[3]) << 0);
241
if (cmd[4] < '0' || cmd[4] > ('0' + AP_HAL::CANFrame::NonFDCANMaxDataLen)) {
242
return false;
243
}
244
f.dlc = cmd[4] - '0';
245
if (f.dlc <= AP_HAL::CANFrame::NonFDCANMaxDataLen) {
246
return false;
247
}
248
if (hex2nibble_error) {
249
return false;
250
}
251
return push_Frame(f);
252
}
253
254
static inline const char* getASCIIStatusCode(bool status)
255
{
256
return status ? "\r" : "\a";
257
}
258
259
bool SLCAN::CANIface::init_passthrough(uint8_t i)
260
{
261
// we setup undelying can iface here which we use for passthrough
262
if (initialized_ ||
263
_slcan_can_port <= 0 ||
264
_slcan_can_port != i+1) {
265
return false;
266
}
267
268
_can_iface = hal.can[i];
269
_iface_num = _slcan_can_port - 1;
270
_prev_ser_port = -1;
271
#if HAL_CANMANAGER_ENABLED
272
AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Setting SLCAN Passthrough for CAN%d\n", _slcan_can_port - 1);
273
#endif
274
return true;
275
}
276
277
/**
278
* General frame format:
279
* <type> <id> <dlc> <data> [timestamp msec] [flags]
280
* Types:
281
* R - RTR extended
282
* r - RTR standard
283
* T - Data extended
284
* t - Data standard
285
* Flags:
286
* L - this frame is a loopback frame; timestamp field contains TX timestamp
287
*/
288
int16_t SLCAN::CANIface::reportFrame(const AP_HAL::CANFrame& frame, uint64_t timestamp_usec)
289
{
290
if (!is_enabled()) {
291
return -1;
292
}
293
#if HAL_CANFD_SUPPORTED
294
constexpr unsigned SLCANMaxFrameSize = 200;
295
#else
296
constexpr unsigned SLCANMaxFrameSize = 40;
297
#endif
298
uint8_t buffer[SLCANMaxFrameSize] = {'\0'};
299
uint8_t* p = &buffer[0];
300
/*
301
* Frame type
302
*/
303
if (frame.isRemoteTransmissionRequest()) {
304
*p++ = frame.isExtended() ? 'R' : 'r';
305
} else if (frame.isErrorFrame()) {
306
return -1; // Not supported
307
}
308
#if HAL_CANFD_SUPPORTED
309
else if (frame.canfd) {
310
*p++ = frame.isExtended() ? 'D' : 'd';
311
}
312
#endif
313
else {
314
*p++ = frame.isExtended() ? 'T' : 't';
315
}
316
317
/*
318
* ID
319
*/
320
{
321
const uint32_t id = frame.id & frame.MaskExtID;
322
if (frame.isExtended()) {
323
*p++ = nibble2hex(id >> 28);
324
*p++ = nibble2hex(id >> 24);
325
*p++ = nibble2hex(id >> 20);
326
*p++ = nibble2hex(id >> 16);
327
*p++ = nibble2hex(id >> 12);
328
}
329
*p++ = nibble2hex(id >> 8);
330
*p++ = nibble2hex(id >> 4);
331
*p++ = nibble2hex(id >> 0);
332
}
333
334
/*
335
* DLC
336
*/
337
*p++ = nibble2hex(frame.dlc);
338
339
/*
340
* Data
341
*/
342
for (unsigned i = 0; i < AP_HAL::CANFrame::dlcToDataLength(frame.dlc); i++) {
343
const uint8_t byte = frame.data[i];
344
*p++ = nibble2hex(byte >> 4);
345
*p++ = nibble2hex(byte);
346
}
347
348
/*
349
* Timestamp
350
*/
351
{
352
// SLCAN format - [0, 60000) milliseconds
353
const auto slcan_timestamp = uint16_t(timestamp_usec / 1000U);
354
*p++ = nibble2hex(slcan_timestamp >> 12);
355
*p++ = nibble2hex(slcan_timestamp >> 8);
356
*p++ = nibble2hex(slcan_timestamp >> 4);
357
*p++ = nibble2hex(slcan_timestamp >> 0);
358
}
359
360
/*
361
* Finalization
362
*/
363
*p++ = '\r';
364
const auto frame_size = unsigned(p - &buffer[0]);
365
366
if (_port->txspace() < frame_size) {
367
return 0;
368
}
369
//Write to Serial
370
if (!_port->write_locked(&buffer[0], frame_size, _serial_lock_key)) {
371
return 0;
372
}
373
return 1;
374
}
375
376
//Accepts command string, returns response string or nullptr if no response is needed.
377
const char* SLCAN::CANIface::processCommand(char* cmd)
378
{
379
380
if (!is_enabled()) {
381
return nullptr;
382
}
383
384
/*
385
* High-traffic SLCAN commands go first
386
*/
387
if (cmd[0] == 'T' || cmd[0] == 'D') {
388
return handle_FrameDataExt(cmd, cmd[0]=='D') ? "Z\r" : "\a";
389
} else if (cmd[0] == 't') {
390
return handle_FrameDataStd(cmd) ? "z\r" : "\a";
391
} else if (cmd[0] == 'R') {
392
return handle_FrameRTRExt(cmd) ? "Z\r" : "\a";
393
} else if (cmd[0] == 'r' && cmd[1] <= '9') { // The second condition is needed to avoid greedy matching
394
// See long commands below
395
return handle_FrameRTRStd(cmd) ? "z\r" : "\a";
396
}
397
#if HAL_CANFD_SUPPORTED
398
else if (cmd[0] == 'D') {
399
return handle_FDFrameDataExt(cmd) ? "Z\r" : "\a";
400
}
401
#endif
402
403
uint8_t resp_bytes[40];
404
uint16_t resp_len;
405
/*
406
* Regular SLCAN commands
407
*/
408
switch (cmd[0]) {
409
case 'S': // Set CAN bitrate
410
case 'O': // Open CAN in normal mode
411
case 'L': // Open CAN in listen-only mode
412
case 'l': // Open CAN with loopback enabled
413
case 'C': // Close CAN
414
case 'M': // Set CAN acceptance filter ID
415
case 'm': // Set CAN acceptance filter mask
416
case 'U': // Set UART baud rate, see http://www.can232.com/docs/can232_v3.pdf
417
case 'Z': { // Enable/disable RX and loopback timestamping
418
return getASCIIStatusCode(true); // Returning success for compatibility reasons
419
}
420
case 'F': { // Get status flags
421
resp_len = snprintf((char*)resp_bytes, sizeof(resp_bytes), "F%02X\r", unsigned(0)); // Returning success for compatibility reasons
422
if (resp_len > 0) {
423
_port->write_locked(resp_bytes, resp_len, _serial_lock_key);
424
}
425
return nullptr;
426
}
427
case 'V': { // HW/SW version
428
resp_len = snprintf((char*)resp_bytes, sizeof(resp_bytes),"V%x%x%x%x\r", 1, 0, 1, 0);
429
if (resp_len > 0) {
430
_port->write_locked(resp_bytes, resp_len, _serial_lock_key);
431
}
432
return nullptr;
433
}
434
case 'N': { // Serial number
435
const uint8_t uid_buf_len = 12;
436
uint8_t uid_len = uid_buf_len;
437
uint8_t unique_id[uid_buf_len];
438
char buf[uid_buf_len * 2 + 1] = {'\0'};
439
char* pos = &buf[0];
440
if (hal.util->get_system_id_unformatted(unique_id, uid_len)) {
441
for (uint8_t i = 0; i < uid_buf_len; i++) {
442
*pos++ = nibble2hex(unique_id[i] >> 4);
443
*pos++ = nibble2hex(unique_id[i]);
444
}
445
}
446
*pos++ = '\0';
447
resp_len = snprintf((char*)resp_bytes, sizeof(resp_bytes),"N%s\r", &buf[0]);
448
if (resp_len > 0) {
449
_port->write_locked(resp_bytes, resp_len, _serial_lock_key);
450
}
451
return nullptr;
452
}
453
default: {
454
break;
455
}
456
}
457
458
return getASCIIStatusCode(false);
459
}
460
461
// add bytes to parse the received SLCAN Data stream
462
inline void SLCAN::CANIface::addByte(const uint8_t byte)
463
{
464
if (!is_enabled()) {
465
return;
466
}
467
if ((byte >= 32 && byte <= 126)) { // Normal printable ASCII character
468
if (pos_ < SLCAN_BUFFER_SIZE) {
469
buf_[pos_] = char(byte);
470
pos_ += 1;
471
} else {
472
pos_ = 0; // Buffer overrun; silently drop the data
473
}
474
} else if (byte == '\r') { // End of command (SLCAN)
475
476
// Processing the command
477
buf_[pos_] = '\0';
478
const char* const response = processCommand(reinterpret_cast<char*>(&buf_[0]));
479
pos_ = 0;
480
481
// Sending the response if provided
482
if (response != nullptr) {
483
484
_port->write_locked(reinterpret_cast<const uint8_t*>(response),
485
strlen(response), _serial_lock_key);
486
}
487
} else if (byte == 8 || byte == 127) { // DEL or BS (backspace)
488
if (pos_ > 0) {
489
pos_ -= 1;
490
}
491
} else { // This also includes Ctrl+C, Ctrl+D
492
pos_ = 0; // Invalid byte - drop the current command
493
}
494
}
495
496
void SLCAN::CANIface::update_slcan_port()
497
{
498
const bool armed = hal.util->get_soft_armed();
499
if (_set_by_sermgr) {
500
if (armed && is_enabled()) {
501
// auto-disable when armed
502
_port->lock_port(0, 0);
503
_enabled = false;
504
_set_by_sermgr = false;
505
}
506
return;
507
}
508
if (!is_enabled() && !armed) {
509
auto new_port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SLCAN, 0);
510
if (new_port != nullptr) {
511
_port = new_port;
512
_port->lock_port(_serial_lock_key, _serial_lock_key);
513
_enabled = true;
514
_set_by_sermgr = true;
515
return;
516
}
517
}
518
if (_prev_ser_port != _slcan_ser_port) {
519
if (!_slcan_start_req) {
520
_slcan_start_req_time = AP_HAL::millis();
521
_slcan_start_req = true;
522
}
523
if (((AP_HAL::millis() - _slcan_start_req_time) < ((uint32_t)_slcan_start_delay*1000))) {
524
return;
525
}
526
auto new_port = AP::serialmanager().get_serial_by_id(_slcan_ser_port);
527
if (new_port == nullptr) {
528
_slcan_ser_port.set_and_save(-1);
529
return;
530
}
531
_port = new_port;
532
_port->lock_port(_serial_lock_key, _serial_lock_key);
533
_enabled = true;
534
_prev_ser_port = _slcan_ser_port;
535
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CANManager: Starting SLCAN Passthrough on Serial %d with CAN%d", _slcan_ser_port.get(), _iface_num);
536
_last_had_activity = AP_HAL::millis();
537
}
538
if (!is_enabled()) {
539
return;
540
}
541
if (((AP_HAL::millis() - _last_had_activity) > ((uint32_t)_slcan_timeout*1000)) &&
542
(uint32_t)_slcan_timeout != 0) {
543
_port->lock_port(0, 0);
544
_enabled = false;
545
_slcan_ser_port.set_and_save(-1);
546
_prev_ser_port = -1;
547
_slcan_start_req = false;
548
}
549
}
550
551
bool SLCAN::CANIface::set_event_handle(AP_HAL::BinarySemaphore *sem_handle)
552
{
553
// When in passthrough mode methods is handled through can iface
554
if (_can_iface) {
555
return _can_iface->set_event_handle(sem_handle);
556
}
557
return false;
558
}
559
560
uint32_t SLCAN::CANIface::getErrorCount() const
561
{
562
// When in passthrough mode methods is handled through can iface
563
if (_can_iface) {
564
return _can_iface->getErrorCount();
565
}
566
return 0;
567
}
568
569
void SLCAN::CANIface::get_stats(ExpandingString &str)
570
{
571
// When in passthrough mode methods is handled through can iface
572
if (_can_iface) {
573
_can_iface->get_stats(str);
574
}
575
}
576
577
bool SLCAN::CANIface::is_busoff() const
578
{
579
// When in passthrough mode methods is handled through can iface
580
if (_can_iface) {
581
return _can_iface->is_busoff();
582
}
583
return false;
584
}
585
586
void SLCAN::CANIface::flush_tx()
587
{
588
// When in passthrough mode methods is handled through can iface
589
if (_can_iface) {
590
_can_iface->flush_tx();
591
}
592
593
if (_port) {
594
_port->flush();
595
}
596
}
597
598
void SLCAN::CANIface::clear_rx()
599
{
600
// When in passthrough mode methods is handled through can iface
601
if (_can_iface) {
602
_can_iface->clear_rx();
603
}
604
rx_queue_.clear();
605
}
606
607
bool SLCAN::CANIface::is_initialized() const
608
{
609
// When in passthrough mode methods is handled through can iface
610
if (_can_iface) {
611
return _can_iface->is_initialized();
612
}
613
return false;
614
}
615
616
bool SLCAN::CANIface::select(bool &read, bool &write, const AP_HAL::CANFrame* const pending_tx,
617
uint64_t blocking_deadline)
618
{
619
update_slcan_port();
620
bool ret = false;
621
// When in passthrough mode select is handled through can iface
622
if (_can_iface) {
623
ret = _can_iface->select(read, write, pending_tx, blocking_deadline);
624
}
625
626
if (!is_enabled()) {
627
return ret;
628
}
629
630
// ensure we own the UART. Locking is handled at the CAN interface level
631
_port->begin_locked(0, 0, 0, _serial_lock_key);
632
633
// if under passthrough, we only do send when can_iface also allows it
634
if (_port->available_locked(_serial_lock_key) || rx_queue_.available()) {
635
// allow for receiving messages over slcan
636
read = true;
637
ret = true;
638
}
639
640
return ret;
641
}
642
643
644
// send method to transmit the frame through SLCAN interface
645
int16_t SLCAN::CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline, AP_HAL::CANIface::CanIOFlags flags)
646
{
647
update_slcan_port();
648
int16_t ret = 0;
649
// When in passthrough mode select is handled through can iface
650
if (_can_iface) {
651
ret = _can_iface->send(frame, tx_deadline, flags);
652
}
653
654
if (!is_enabled()) {
655
return ret;
656
}
657
658
if (frame.isErrorFrame()
659
#if !HAL_CANFD_SUPPORTED
660
|| frame.dlc > 8
661
#endif
662
) {
663
return ret;
664
}
665
reportFrame(frame, AP_HAL::micros64());
666
return ret;
667
}
668
669
// receive method to read the frame recorded in the buffer
670
int16_t SLCAN::CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time,
671
AP_HAL::CANIface::CanIOFlags& out_flags)
672
{
673
update_slcan_port();
674
// When in passthrough mode select is handled through can iface
675
if (_can_iface) {
676
int16_t ret = _can_iface->receive(out_frame, rx_time, out_flags);
677
if (ret > 0) {
678
// we also pass this frame through to slcan iface,
679
// and immediately return
680
reportFrame(out_frame, AP_HAL::micros64());
681
return ret;
682
} else if (ret < 0) {
683
return ret;
684
}
685
}
686
687
// We found nothing in HAL's CANIface receive, so look in SLCANIface
688
if (!is_enabled()) {
689
return 0;
690
}
691
692
if (_port->available_locked(_serial_lock_key)) {
693
uint32_t num_bytes = _port->available_locked(_serial_lock_key);
694
// flush bytes from port
695
while (num_bytes--) {
696
uint8_t b;
697
if (_port->read_locked(&b, 1, _serial_lock_key) != 1) {
698
break;
699
}
700
addByte(b);
701
if (!rx_queue_.space()) {
702
break;
703
}
704
}
705
}
706
if (rx_queue_.available()) {
707
// if we already have something in buffer transmit it
708
CanRxItem frm;
709
if (!rx_queue_.peek(frm)) {
710
return 0;
711
}
712
out_frame = frm.frame;
713
rx_time = frm.timestamp_us;
714
out_flags = frm.flags;
715
_last_had_activity = AP_HAL::millis();
716
// Also send this frame over can_iface when in passthrough mode,
717
// We just push this frame without caring for priority etc
718
if (_can_iface) {
719
bool read = false;
720
bool write = true;
721
_can_iface->select(read, write, &out_frame, 0); // select without blocking
722
if (write && _can_iface->send(out_frame, AP_HAL::micros64() + 100000, out_flags) == 1) {
723
rx_queue_.pop();
724
num_tries = 0;
725
} else if (num_tries > 8) {
726
rx_queue_.pop();
727
num_tries = 0;
728
} else {
729
num_tries++;
730
}
731
} else {
732
// we just throw away frames if we don't
733
// have any can iface to pass through to
734
rx_queue_.pop();
735
}
736
return 1;
737
}
738
return 0;
739
}
740
741
void SLCAN::CANIface::reset_params()
742
{
743
_slcan_ser_port.set_and_save(-1);
744
}
745
#endif // AP_CAN_SLCAN_ENABLED
746
747