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_serial.cpp
Views: 1798
1
/*
2
map local serial ports to remote DroneCAN serial ports using the
3
TUNNEL_TARGETTED message
4
*/
5
6
#include "AP_DroneCAN.h"
7
8
#if HAL_ENABLE_DRONECAN_DRIVERS && AP_DRONECAN_SERIAL_ENABLED
9
10
#include <AP_Math/AP_Math.h>
11
#include <AP_BoardConfig/AP_BoardConfig.h>
12
13
AP_DroneCAN_Serial *AP_DroneCAN_Serial::serial[HAL_MAX_CAN_PROTOCOL_DRIVERS];
14
15
#ifndef AP_DRONECAN_SERIAL_MIN_TXSIZE
16
#define AP_DRONECAN_SERIAL_MIN_TXSIZE 2048
17
#endif
18
19
#ifndef AP_DRONECAN_SERIAL_MIN_RXSIZE
20
#define AP_DRONECAN_SERIAL_MIN_RXSIZE 2048
21
#endif
22
23
/*
24
initialise DroneCAN serial aports
25
*/
26
void AP_DroneCAN_Serial::init(AP_DroneCAN *_dronecan)
27
{
28
if (enable == 0) {
29
return;
30
}
31
const uint8_t driver_index = _dronecan->get_driver_index();
32
if (driver_index >= ARRAY_SIZE(serial)) {
33
return;
34
}
35
serial[driver_index] = this;
36
dronecan = _dronecan;
37
38
const uint8_t base_port = driver_index == 0? AP_SERIALMANAGER_CAN_D1_PORT_1 : AP_SERIALMANAGER_CAN_D2_PORT_1;
39
bool need_subscriber = false;
40
41
for (uint8_t i=0; i<ARRAY_SIZE(ports); i++) {
42
auto &p = ports[i];
43
p.state.idx = base_port + i;
44
if (p.node > 0 && p.idx >= 0) {
45
p.init();
46
AP::serialmanager().register_port(&p);
47
need_subscriber = true;
48
}
49
}
50
51
if (need_subscriber) {
52
if (Canard::allocate_sub_arg_callback(dronecan, &handle_tunnel_targetted, dronecan->get_driver_index()) == nullptr) {
53
AP_BoardConfig::allocation_error("serial_tunnel_sub");
54
}
55
targetted = NEW_NOTHROW Canard::Publisher<uavcan_tunnel_Targetted>(dronecan->get_canard_iface());
56
if (targetted == nullptr) {
57
AP_BoardConfig::allocation_error("serial_tunnel_pub");
58
}
59
targetted->set_timeout_ms(20);
60
targetted->set_priority(CANARD_TRANSFER_PRIORITY_MEDIUM);
61
}
62
}
63
64
/*
65
update DroneCAN serial ports
66
*/
67
void AP_DroneCAN_Serial::update(void)
68
{
69
const uint32_t now_ms = AP_HAL::millis();
70
for (auto &p : ports) {
71
if (p.baudrate == 0) {
72
continue;
73
}
74
if (p.writebuffer == nullptr || p.node <= 0 || p.idx < 0) {
75
continue;
76
}
77
uavcan_tunnel_Targetted pkt {};
78
uint32_t n = 0;
79
{
80
WITH_SEMAPHORE(p.sem);
81
uint32_t avail;
82
const bool send_keepalive = now_ms - p.last_send_ms > 500;
83
const auto *ptr = p.writebuffer->readptr(avail);
84
if (!send_keepalive && (ptr == nullptr || avail <= 0)) {
85
continue;
86
}
87
n = MIN(avail, sizeof(pkt.buffer.data));
88
pkt.target_node = p.node;
89
switch (p.state.protocol) {
90
case AP_SerialManager::SerialProtocol_MAVLink:
91
pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_MAVLINK;
92
break;
93
case AP_SerialManager::SerialProtocol_MAVLink2:
94
pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_MAVLINK2;
95
break;
96
case AP_SerialManager::SerialProtocol_GPS:
97
case AP_SerialManager::SerialProtocol_GPS2: // is not in SERIAL1_PROTOCOL option list, but could be entered by user
98
pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_GPS_GENERIC;
99
break;
100
default:
101
pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_UNDEFINED;
102
}
103
pkt.buffer.len = n;
104
pkt.baudrate = p.baudrate;
105
pkt.serial_id = p.idx;
106
pkt.options = UAVCAN_TUNNEL_TARGETTED_OPTION_LOCK_PORT;
107
if (ptr != nullptr) {
108
memcpy(pkt.buffer.data, ptr, n);
109
}
110
}
111
if (targetted->broadcast(pkt)) {
112
WITH_SEMAPHORE(p.sem);
113
p.writebuffer->advance(n);
114
p.last_send_ms = now_ms;
115
}
116
}
117
}
118
119
/*
120
handle incoming tunnel serial packet
121
*/
122
void AP_DroneCAN_Serial::handle_tunnel_targetted(AP_DroneCAN *dronecan,
123
const CanardRxTransfer& transfer,
124
const uavcan_tunnel_Targetted &msg)
125
{
126
uint8_t driver_index = dronecan->get_driver_index();
127
if (driver_index >= ARRAY_SIZE(serial) || serial[driver_index] == nullptr) {
128
return;
129
}
130
auto &s = *serial[driver_index];
131
for (auto &p : s.ports) {
132
if (p.idx == msg.serial_id && transfer.source_node_id == p.node) {
133
WITH_SEMAPHORE(p.sem);
134
if (p.readbuffer != nullptr) {
135
p.readbuffer->write(msg.buffer.data, msg.buffer.len);
136
p.last_recv_us = AP_HAL::micros64();
137
}
138
break;
139
}
140
}
141
}
142
143
/*
144
initialise port
145
*/
146
void AP_DroneCAN_Serial::Port::init(void)
147
{
148
baudrate = AP_SerialManager::map_baudrate(state.baud);
149
begin(baudrate, 0, 0);
150
}
151
152
/*
153
available space in outgoing buffer
154
*/
155
uint32_t AP_DroneCAN_Serial::Port::txspace(void)
156
{
157
WITH_SEMAPHORE(sem);
158
return writebuffer != nullptr ? writebuffer->space() : 0;
159
}
160
161
void AP_DroneCAN_Serial::Port::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
162
{
163
rxS = MAX(rxS, AP_DRONECAN_SERIAL_MIN_RXSIZE);
164
txS = MAX(txS, AP_DRONECAN_SERIAL_MIN_TXSIZE);
165
init_buffers(rxS, txS);
166
if (b != 0) {
167
baudrate = b;
168
}
169
}
170
171
size_t AP_DroneCAN_Serial::Port::_write(const uint8_t *buffer, size_t size)
172
{
173
WITH_SEMAPHORE(sem);
174
return writebuffer != nullptr ? writebuffer->write(buffer, size) : 0;
175
}
176
177
ssize_t AP_DroneCAN_Serial::Port::_read(uint8_t *buffer, uint16_t count)
178
{
179
WITH_SEMAPHORE(sem);
180
return readbuffer != nullptr ? readbuffer->read(buffer, count) : -1;
181
}
182
183
uint32_t AP_DroneCAN_Serial::Port::_available()
184
{
185
WITH_SEMAPHORE(sem);
186
return readbuffer != nullptr ? readbuffer->available() : 0;
187
}
188
189
190
bool AP_DroneCAN_Serial::Port::_discard_input()
191
{
192
WITH_SEMAPHORE(sem);
193
if (readbuffer != nullptr) {
194
readbuffer->clear();
195
}
196
return true;
197
}
198
199
/*
200
initialise read/write buffers
201
*/
202
bool AP_DroneCAN_Serial::Port::init_buffers(const uint32_t size_rx, const uint32_t size_tx)
203
{
204
if (size_tx == last_size_tx &&
205
size_rx == last_size_rx) {
206
return true;
207
}
208
WITH_SEMAPHORE(sem);
209
if (readbuffer == nullptr) {
210
readbuffer = NEW_NOTHROW ByteBuffer(size_rx);
211
} else {
212
readbuffer->set_size_best(size_rx);
213
}
214
if (writebuffer == nullptr) {
215
writebuffer = NEW_NOTHROW ByteBuffer(size_tx);
216
} else {
217
writebuffer->set_size_best(size_tx);
218
}
219
last_size_rx = size_rx;
220
last_size_tx = size_tx;
221
return readbuffer != nullptr && writebuffer != nullptr;
222
}
223
224
/*
225
return timestamp estimate in microseconds for when the start of
226
a nbytes packet arrived on the uart.
227
*/
228
uint64_t AP_DroneCAN_Serial::Port::receive_time_constraint_us(uint16_t nbytes)
229
{
230
WITH_SEMAPHORE(sem);
231
uint64_t last_receive_us = last_recv_us;
232
if (baudrate > 0) {
233
// assume 10 bits per byte.
234
uint32_t transport_time_us = (1000000UL * 10UL / baudrate) * (nbytes+available());
235
last_receive_us -= transport_time_us;
236
}
237
return last_receive_us;
238
}
239
240
#endif // HAL_ENABLE_DRONECAN_DRIVERS && AP_DRONECAN_SERIAL_ENABLED
241
242