Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/serial_tunnel.cpp
9377 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
handle tunnelling of serial data over DroneCAN
17
*/
18
19
#include <AP_HAL/AP_HAL_Boards.h>
20
#include "AP_Periph.h"
21
22
#if AP_UART_MONITOR_ENABLED
23
24
#include <dronecan_msgs.h>
25
26
extern const AP_HAL::HAL &hal;
27
28
#define TUNNEL_LOCK_KEY 0xf2e460e4U
29
30
#ifndef TUNNEL_DEBUG
31
#define TUNNEL_DEBUG 0
32
#endif
33
34
#if TUNNEL_DEBUG
35
# define debug(fmt, args...) can_printf(fmt "\n", ##args)
36
#else
37
# define debug(fmt, args...)
38
#endif
39
40
/*
41
get the default port to tunnel if the client requests port -1
42
*/
43
int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const
44
{
45
int8_t uart_num = -1;
46
#if AP_PERIPH_GPS_ENABLED
47
if (uart_num == -1) {
48
uart_num = g.gps_port;
49
}
50
#endif
51
#if AP_PERIPH_RANGEFINDER_ENABLED
52
if (uart_num == -1) {
53
uart_num = g.rangefinder_port[0];
54
}
55
#endif
56
#if AP_PERIPH_ADSB_ENABLED
57
if (uart_num == -1) {
58
uart_num = g.adsb_port;
59
}
60
#endif
61
#if AP_PERIPH_PROXIMITY_ENABLED
62
if (uart_num == -1) {
63
uart_num = g.proximity_port;
64
}
65
#endif
66
return uart_num;
67
}
68
69
/*
70
handle tunnel data
71
*/
72
void AP_Periph_FW::handle_tunnel_Targetted(CanardInstance* canard_ins, CanardRxTransfer* transfer)
73
{
74
uavcan_tunnel_Targetted pkt;
75
if (uavcan_tunnel_Targetted_decode(transfer, &pkt)) {
76
return;
77
}
78
if (pkt.target_node != canardGetLocalNodeID(canard_ins)) {
79
return;
80
}
81
int8_t uart_num = pkt.serial_id;
82
if (uart_num == -1) {
83
uart_num = get_default_tunnel_serial_port();
84
}
85
if (uart_num < 0) {
86
return;
87
}
88
if (uint8_t(uart_num) > ARRAY_SIZE(uart_monitors)) {
89
return;
90
}
91
auto &uart_monitor = uart_monitors[uart_num];
92
if (uart_monitor.uart == nullptr) {
93
auto *uart = hal.serial(uart_num);
94
if (uart == nullptr) {
95
return;
96
}
97
if (uart_monitor.buffer == nullptr) {
98
uart_monitor.buffer = NEW_NOTHROW ByteBuffer(1024);
99
if (uart_monitor.buffer == nullptr) {
100
return;
101
}
102
uart_monitor.uart_num = uart_num;
103
}
104
uart_monitor.baudrate = 0;
105
uart_monitor.uart = uart; // setting this indicates the monitor is set up
106
uart_monitor.uart->set_monitor_read_buffer(uart_monitor.buffer);
107
}
108
if (uart_monitor.uart == nullptr) {
109
return;
110
}
111
/*
112
allow for locked state to change at any time, so users can
113
switch between locked and unlocked while connected
114
*/
115
const bool was_locked = uart_monitor.locked;
116
uart_monitor.locked = (pkt.options & UAVCAN_TUNNEL_TARGETTED_OPTION_LOCK_PORT) != 0;
117
if (uart_monitor.locked) {
118
uart_monitor.uart->lock_port(TUNNEL_LOCK_KEY, TUNNEL_LOCK_KEY);
119
} else {
120
uart_monitor.uart->lock_port(0,0);
121
}
122
uart_monitor.node_id = transfer->source_node_id;
123
uart_monitor.protocol = pkt.protocol.protocol;
124
if (pkt.baudrate != uart_monitor.baudrate || !was_locked) {
125
if (uart_monitor.locked && pkt.baudrate != 0) {
126
// ensure we have enough buffer space for a uBlox fw update and fast uCenter data
127
uart_monitor.uart->begin_locked(pkt.baudrate, 2048, 2048, TUNNEL_LOCK_KEY);
128
debug("begin_locked %u", unsigned(pkt.baudrate));
129
}
130
uart_monitor.baudrate = pkt.baudrate;
131
}
132
uart_monitor.last_request_ms = AP_HAL::millis();
133
134
// write to device
135
if (pkt.buffer.len > 0) {
136
if (uart_monitor.locked) {
137
debug("write_locked %u", unsigned(pkt.buffer.len));
138
uart_monitor.uart->write_locked(pkt.buffer.data, pkt.buffer.len, TUNNEL_LOCK_KEY);
139
} else {
140
uart_monitor.uart->write(pkt.buffer.data, pkt.buffer.len);
141
}
142
} else {
143
debug("locked keepalive");
144
}
145
}
146
147
/*
148
send tunnelled serial data
149
*/
150
void AP_Periph_FW::send_serial_monitor_data()
151
{
152
for (auto &m : uart_monitors) {
153
send_serial_monitor_data_instance(m);
154
}
155
}
156
157
void AP_Periph_FW::send_serial_monitor_data_instance(AP_Periph_FW::UARTMonitor &uart_monitor)
158
{
159
if (uart_monitor.uart == nullptr ||
160
uart_monitor.node_id == 0 ||
161
uart_monitor.buffer == nullptr) {
162
return;
163
}
164
const uint32_t last_req_ms = uart_monitor.last_request_ms;
165
const uint32_t now_ms = AP_HAL::millis();
166
if (now_ms - last_req_ms >= 3000) {
167
// stop sending and unlock, but don't release the buffer
168
if (uart_monitor.locked) {
169
debug("unlock");
170
uart_monitor.uart->lock_port(0, 0);
171
}
172
uart_monitor.uart = nullptr;
173
return;
174
}
175
if (uart_monitor.locked) {
176
/*
177
when the port is locked nobody is reading the uart so the
178
monitor doesn't fill. We read here to ensure it fills
179
*/
180
uint8_t buf[120];
181
for (uint8_t i=0; i<8; i++) {
182
if (uart_monitor.uart->read_locked(buf, sizeof(buf), TUNNEL_LOCK_KEY) <= 0) {
183
break;
184
}
185
}
186
}
187
uint8_t sends = 8;
188
while (uart_monitor.buffer->available() > 0 && sends-- > 0) {
189
uint32_t n;
190
const uint8_t *buf = uart_monitor.buffer->readptr(n);
191
if (n == 0) {
192
return;
193
}
194
// broadcast data as tunnel packets, can be used for uCenter debug and device fw update
195
uavcan_tunnel_Targetted pkt {};
196
n = MIN(n, sizeof(pkt.buffer.data));
197
pkt.target_node = uart_monitor.node_id;
198
pkt.protocol.protocol = uart_monitor.protocol;
199
pkt.buffer.len = n;
200
pkt.baudrate = uart_monitor.baudrate;
201
pkt.serial_id = uart_monitor.uart_num;
202
memcpy(pkt.buffer.data, buf, n);
203
204
uint8_t buffer[UAVCAN_TUNNEL_TARGETTED_MAX_SIZE];
205
const uint16_t total_size = uavcan_tunnel_Targetted_encode(&pkt, buffer, !canfdout());
206
207
debug("read %u", unsigned(n));
208
209
if (!canard_broadcast(UAVCAN_TUNNEL_TARGETTED_SIGNATURE,
210
UAVCAN_TUNNEL_TARGETTED_ID,
211
CANARD_TRANSFER_PRIORITY_MEDIUM,
212
&buffer[0],
213
total_size)) {
214
break;
215
}
216
uart_monitor.buffer->advance(n);
217
}
218
}
219
#endif // AP_UART_MONITOR_ENABLED
220
221