Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_CANManager/AP_MAVLinkCAN.cpp
4182 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
16
#include "AP_MAVLinkCAN.h"
17
#include <AP_HAL/utility/sparse-endian.h>
18
#include <AP_Common/sorting.h>
19
20
#if HAL_CANMANAGER_ENABLED && HAL_GCS_ENABLED
21
22
extern const AP_HAL::HAL& hal;
23
24
/*
25
handle MAV_CMD_CAN_FORWARD mavlink long command
26
*/
27
bool AP_MAVLinkCAN::handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg)
28
{
29
WITH_SEMAPHORE(can_forward.sem);
30
const int8_t bus = int8_t(packet.param1)-1;
31
32
if (bus == -1) {
33
/*
34
a request to stop forwarding
35
*/
36
if (can_forward.callback_id != 0) {
37
hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);
38
can_forward.callback_id = 0;
39
}
40
return true;
41
}
42
43
if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {
44
return false;
45
}
46
47
if (can_forward.callback_id != 0 && can_forward.callback_bus != bus) {
48
/*
49
the client is changing which bus they are monitoring, unregister from the previous bus
50
*/
51
hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);
52
can_forward.callback_id = 0;
53
}
54
55
if (can_forward.callback_id == 0 &&
56
!hal.can[bus]->register_frame_callback(
57
FUNCTOR_BIND_MEMBER(&AP_MAVLinkCAN::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags), can_forward.callback_id)) {
58
// failed to register the callback
59
return false;
60
}
61
62
can_forward.callback_bus = bus;
63
can_forward.last_callback_enable_ms = AP_HAL::millis();
64
can_forward.chan = chan;
65
can_forward.system_id = msg.sysid;
66
can_forward.component_id = msg.compid;
67
68
return true;
69
}
70
71
/*
72
handle a CAN_FRAME packet
73
*/
74
void AP_MAVLinkCAN::handle_can_frame(const mavlink_message_t &msg)
75
{
76
if (frame_buffer == nullptr) {
77
// allocate frame buffer
78
// 20 is good for firmware upload
79
uint8_t buffer_size = 20;
80
WITH_SEMAPHORE(frame_buffer_sem);
81
while (frame_buffer == nullptr && buffer_size > 0) {
82
// we'd like 20 frames, but will live with less
83
frame_buffer = NEW_NOTHROW ObjectBuffer<BufferFrame>(buffer_size);
84
if (frame_buffer != nullptr && frame_buffer->get_size() != 0) {
85
// register a callback for when frames can't be sent immediately
86
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_MAVLinkCAN::process_frame_buffer, void));
87
break;
88
}
89
delete frame_buffer;
90
frame_buffer = nullptr;
91
buffer_size /= 2;
92
}
93
if (frame_buffer == nullptr) {
94
// discard the frames
95
return;
96
}
97
}
98
99
switch (msg.msgid) {
100
case MAVLINK_MSG_ID_CAN_FRAME: {
101
mavlink_can_frame_t p;
102
mavlink_msg_can_frame_decode(&msg, &p);
103
if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {
104
return;
105
}
106
struct BufferFrame frame {
107
bus : p.bus,
108
frame : AP_HAL::CANFrame(p.id, p.data, p.len)
109
};
110
{
111
WITH_SEMAPHORE(frame_buffer_sem);
112
frame_buffer->push(frame);
113
}
114
break;
115
}
116
#if HAL_CANFD_SUPPORTED
117
case MAVLINK_MSG_ID_CANFD_FRAME: {
118
mavlink_canfd_frame_t p;
119
mavlink_msg_canfd_frame_decode(&msg, &p);
120
if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {
121
return;
122
}
123
struct BufferFrame frame {
124
bus : p.bus,
125
frame : AP_HAL::CANFrame(p.id, p.data, p.len, true)
126
};
127
{
128
WITH_SEMAPHORE(frame_buffer_sem);
129
frame_buffer->push(frame);
130
}
131
break;
132
}
133
#endif
134
}
135
process_frame_buffer();
136
}
137
138
/*
139
process the frame buffer
140
*/
141
void AP_MAVLinkCAN::process_frame_buffer()
142
{
143
while (frame_buffer) {
144
WITH_SEMAPHORE(frame_buffer_sem);
145
struct BufferFrame frame;
146
const uint16_t timeout_us = 2000;
147
if (!frame_buffer->peek(frame)) {
148
// no frames in the queue
149
break;
150
}
151
const int16_t retcode = hal.can[frame.bus]->send(frame.frame,
152
AP_HAL::micros64() + timeout_us,
153
AP_HAL::CANIface::IsForwardedFrame);
154
if (retcode == 0) {
155
// no space in the CAN output slots, try again later
156
break;
157
}
158
// retcode == 1 means sent, -1 means a frame that can't be
159
// sent. Either way we should remove from the queue
160
frame_buffer->pop();
161
}
162
}
163
164
/*
165
handle a CAN_FILTER_MODIFY packet
166
*/
167
void AP_MAVLinkCAN::handle_can_filter_modify(const mavlink_message_t &msg)
168
{
169
mavlink_can_filter_modify_t p;
170
mavlink_msg_can_filter_modify_decode(&msg, &p);
171
const int8_t bus = int8_t(p.bus)-1;
172
if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {
173
return;
174
}
175
if (p.num_ids > ARRAY_SIZE(p.ids)) {
176
return;
177
}
178
uint16_t *new_ids = nullptr;
179
uint16_t num_new_ids = 0;
180
WITH_SEMAPHORE(can_forward.sem);
181
182
// sort the list, so we can bisection search and the array
183
// operations below are efficient
184
insertion_sort_uint16(p.ids, p.num_ids);
185
186
switch (p.operation) {
187
case CAN_FILTER_REPLACE: {
188
if (p.num_ids == 0) {
189
can_forward.num_filter_ids = 0;
190
delete[] can_forward.filter_ids;
191
can_forward.filter_ids = nullptr;
192
return;
193
}
194
if (p.num_ids == can_forward.num_filter_ids &&
195
memcmp(p.ids, can_forward.filter_ids, p.num_ids*sizeof(uint16_t)) == 0) {
196
// common case of replacing with identical list
197
return;
198
}
199
new_ids = NEW_NOTHROW uint16_t[p.num_ids];
200
if (new_ids != nullptr) {
201
num_new_ids = p.num_ids;
202
memcpy((void*)new_ids, (const void *)p.ids, p.num_ids*sizeof(uint16_t));
203
}
204
break;
205
}
206
case CAN_FILTER_ADD: {
207
if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,
208
p.ids, p.num_ids) == p.num_ids) {
209
// nothing changing
210
return;
211
}
212
new_ids = NEW_NOTHROW uint16_t[can_forward.num_filter_ids+p.num_ids];
213
if (new_ids == nullptr) {
214
return;
215
}
216
if (can_forward.num_filter_ids != 0) {
217
memcpy(new_ids, can_forward.filter_ids, can_forward.num_filter_ids*sizeof(uint16_t));
218
}
219
memcpy(&new_ids[can_forward.num_filter_ids], p.ids, p.num_ids*sizeof(uint16_t));
220
insertion_sort_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);
221
num_new_ids = remove_duplicates_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);
222
break;
223
}
224
case CAN_FILTER_REMOVE: {
225
if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,
226
p.ids, p.num_ids) == 0) {
227
// nothing changing
228
return;
229
}
230
can_forward.num_filter_ids = remove_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,
231
p.ids, p.num_ids);
232
if (can_forward.num_filter_ids == 0) {
233
delete[] can_forward.filter_ids;
234
can_forward.filter_ids = nullptr;
235
}
236
break;
237
}
238
}
239
if (new_ids != nullptr) {
240
// handle common case of no change
241
if (num_new_ids == can_forward.num_filter_ids &&
242
memcmp(new_ids, can_forward.filter_ids, num_new_ids*sizeof(uint16_t)) == 0) {
243
delete[] new_ids;
244
} else {
245
// put the new list in place
246
delete[] can_forward.filter_ids;
247
can_forward.filter_ids = new_ids;
248
can_forward.num_filter_ids = num_new_ids;
249
}
250
}
251
}
252
253
/*
254
handler for CAN frames from the registered callback, sending frames
255
out as CAN_FRAME or CANFD_FRAME messages
256
*/
257
void AP_MAVLinkCAN::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags)
258
{
259
mavlink_channel_t chan;
260
uint8_t system_id;
261
uint8_t component_id;
262
{
263
WITH_SEMAPHORE(can_forward.sem);
264
if (bus != can_forward.callback_bus) {
265
// we are not registered for forwarding this bus, discard frame
266
return;
267
}
268
if (can_forward.frame_counter++ == 100) {
269
// check every 100 frames for disabling CAN_FRAME send
270
// we stop sending after 5s if the client stops
271
// sending MAV_CMD_CAN_FORWARD requests
272
if (can_forward.callback_id != 0 &&
273
AP_HAL::millis() - can_forward.last_callback_enable_ms > 5000) {
274
hal.can[bus]->unregister_frame_callback(can_forward.callback_id);
275
can_forward.callback_id = 0;
276
return;
277
}
278
can_forward.frame_counter = 0;
279
}
280
if (can_forward.filter_ids != nullptr) {
281
// work out ID of this frame
282
uint16_t id = 0;
283
if ((frame.id&0xff) != 0) {
284
// not anonymous
285
if (frame.id & 0x80) {
286
// service message
287
id = uint8_t(frame.id>>16);
288
} else {
289
// message frame
290
id = uint16_t(frame.id>>8);
291
}
292
}
293
if (!bisect_search_uint16(can_forward.filter_ids, can_forward.num_filter_ids, id)) {
294
return;
295
}
296
}
297
// remeber destination while we hold the mutex
298
chan = can_forward.chan;
299
system_id = can_forward.system_id;
300
component_id = can_forward.component_id;
301
}
302
303
// the rest is run without the can_forward.sem
304
WITH_SEMAPHORE(comm_chan_lock(chan));
305
const uint8_t data_len = AP_HAL::CANFrame::dlcToDataLength(frame.dlc);
306
#if HAL_CANFD_SUPPORTED
307
if (frame.isCanFDFrame()) {
308
if (HAVE_PAYLOAD_SPACE(chan, CANFD_FRAME)) {
309
mavlink_msg_canfd_frame_send(chan, system_id, component_id,
310
bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));
311
}
312
} else
313
#endif
314
{
315
if (HAVE_PAYLOAD_SPACE(chan, CAN_FRAME)) {
316
mavlink_msg_can_frame_send(chan, system_id, component_id,
317
bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));
318
}
319
}
320
}
321
322
#endif // HAL_CANMANAGER_ENABLED && HAL_GCS_ENABLED
323
324