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_AIS/AP_AIS.cpp
Views: 1798
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
// Automatic Identification System, https://gpsd.gitlab.io/gpsd/AIVDM.html
17
18
// ToDo: enable receiving of the Mavlink AIS message, type bitmask?
19
20
#include "AP_AIS.h"
21
22
#if AP_AIS_ENABLED
23
24
#include <AP_Vehicle/AP_Vehicle_Type.h>
25
26
#define AP_AIS_DUMMY_METHODS_ENABLED ((AP_AIS_ENABLED == 2) && !APM_BUILD_TYPE(APM_BUILD_Rover))
27
28
#if !AP_AIS_DUMMY_METHODS_ENABLED
29
30
#include <AP_Logger/AP_Logger.h>
31
#include <AP_SerialManager/AP_SerialManager.h>
32
#include <GCS_MAVLink/GCS_MAVLink.h>
33
#include <GCS_MAVLink/GCS.h>
34
#include <AP_AHRS/AP_AHRS.h>
35
36
const AP_Param::GroupInfo AP_AIS::var_info[] = {
37
38
// @Param: TYPE
39
// @DisplayName: AIS receiver type
40
// @Description: AIS receiver type
41
// @Values: 0:None,1:NMEA AIVDM message
42
// @User: Standard
43
// @RebootRequired: True
44
AP_GROUPINFO_FLAGS("TYPE", 1, AP_AIS, _type, 0, AP_PARAM_FLAG_ENABLE),
45
46
// @Param: LIST_MAX
47
// @DisplayName: AIS vessel list size
48
// @Description: AIS list size of nearest vessels. Longer lists take longer to refresh with lower SRx_ADSB values.
49
// @Range: 1 100
50
// @User: Advanced
51
AP_GROUPINFO("LIST_MAX", 2, AP_AIS, _max_list, 25),
52
53
// @Param: TIME_OUT
54
// @DisplayName: AIS vessel time out
55
// @Description: if no updates are received in this time a vessel will be removed from the list
56
// @Units: s
57
// @Range: 1 2000
58
// @User: Advanced
59
AP_GROUPINFO("TIME_OUT", 3, AP_AIS, _time_out, 600),
60
61
// @Param: LOGGING
62
// @DisplayName: AIS logging options
63
// @Description: Bitmask of AIS logging options
64
// @Bitmask: 0:Log all AIVDM messages,1:Log only unsupported AIVDM messages,2:Log decoded messages
65
// @User: Advanced
66
AP_GROUPINFO("LOGGING", 4, AP_AIS, _log_options, AIS_OPTIONS_LOG_UNSUPPORTED_RAW | AIS_OPTIONS_LOG_DECODED),
67
68
AP_GROUPEND
69
};
70
71
// constructor
72
AP_AIS::AP_AIS()
73
{
74
if (_singleton != nullptr) {
75
AP_HAL::panic("AIS must be singleton");
76
}
77
_singleton = this;
78
79
AP_Param::setup_object_defaults(this, var_info);
80
}
81
82
// return true if AIS is enabled
83
bool AP_AIS::enabled() const
84
{
85
return AISType(_type.get()) != AISType::NONE;
86
}
87
88
// Initialize the AIS object and prepare it for use
89
void AP_AIS::init()
90
{
91
if (!enabled()) {
92
return;
93
}
94
95
_uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_AIS, 0);
96
if (_uart == nullptr) {
97
return;
98
}
99
100
_uart->begin(AP::serialmanager().find_baudrate(AP_SerialManager::SerialProtocol_AIS, 0));
101
}
102
103
// update AIS, expected to be called at 20hz
104
void AP_AIS::update()
105
{
106
if (!_uart || !enabled()) {
107
return;
108
}
109
110
// read any available lines
111
uint32_t nbytes = MIN(_uart->available(),1024U);
112
while (nbytes-- > 0) {
113
const int16_t byte = _uart->read();
114
if (byte == -1) {
115
break;
116
}
117
const char c = byte;
118
if (decode(c)) {
119
const bool log_all = (_log_options & AIS_OPTIONS_LOG_ALL_RAW) != 0;
120
const bool log_unsupported = ((_log_options & AIS_OPTIONS_LOG_UNSUPPORTED_RAW) != 0) && !log_all; // only log unsupported if not logging all
121
122
if (_incoming.total > AIVDM_BUFFER_SIZE) {
123
// no point in trying to decode it wont fit
124
#if HAL_LOGGING_ENABLED
125
if (log_all || log_unsupported) {
126
log_raw(&_incoming);
127
}
128
#endif
129
break;
130
}
131
#if HAL_LOGGING_ENABLED
132
if (log_all) {
133
log_raw(&_incoming);
134
}
135
#endif
136
137
if (_incoming.num == 1 && _incoming.total == 1) {
138
// single part message
139
if (!payload_decode(_incoming.payload) && log_unsupported) {
140
#if HAL_LOGGING_ENABLED
141
// could not decode so log
142
log_raw(&_incoming);
143
#endif
144
}
145
} else if (_incoming.num == _incoming.total) {
146
// last part of a multi part message
147
uint8_t index = 0;
148
uint8_t msg_parts[_incoming.num - 1];
149
for (uint8_t i = 0; i < AIVDM_BUFFER_SIZE; i++) {
150
// look for the rest of the message from the start of the buffer
151
// we assume the message has be received in the correct order
152
if (_AIVDM_buffer[i].num == (index + 1) && _AIVDM_buffer[i].total == _incoming.total && _AIVDM_buffer[i].ID == _incoming.ID) {
153
msg_parts[index] = i;
154
index++;
155
if (index >= _incoming.num) {
156
break;
157
}
158
}
159
}
160
161
// did we find the right number?
162
if (_incoming.num != index) {
163
// could not find all of the message, save messages
164
#if HAL_LOGGING_ENABLED
165
if (log_unsupported) {
166
for (uint8_t i = 0; i < index; i++) {
167
log_raw(&_AIVDM_buffer[msg_parts[i]]);
168
}
169
log_raw(&_incoming);
170
}
171
#endif
172
// remove
173
for (uint8_t i = 0; i < index; i++) {
174
buffer_shift(msg_parts[i]);
175
}
176
break;
177
}
178
179
// combine packets
180
char multi[AIVDM_PAYLOAD_SIZE*_incoming.total];
181
strncpy(multi,_AIVDM_buffer[msg_parts[0]].payload,AIVDM_PAYLOAD_SIZE);
182
for (uint8_t i = 1; i < _incoming.total - 1; i++) {
183
strncat(multi,_AIVDM_buffer[msg_parts[i]].payload,sizeof(multi));
184
}
185
strncat(multi,_incoming.payload,sizeof(multi));
186
#if HAL_LOGGING_ENABLED
187
const bool decoded = payload_decode(multi);
188
#endif
189
for (uint8_t i = 0; i < _incoming.total; i++) {
190
#if HAL_LOGGING_ENABLED
191
// unsupported type, log and discard
192
if (!decoded && log_unsupported) {
193
log_raw(&_AIVDM_buffer[msg_parts[i]]);
194
}
195
#endif
196
buffer_shift(msg_parts[i]);
197
}
198
#if HAL_LOGGING_ENABLED
199
if (!decoded && log_unsupported) {
200
log_raw(&_incoming);
201
}
202
#endif
203
} else {
204
// multi part message, store in buffer
205
bool fits_in = false;
206
for (uint8_t i = 0; i < AIVDM_BUFFER_SIZE; i++) {
207
// find the first free spot
208
if (_AIVDM_buffer[i].num == 0 && _AIVDM_buffer[i].total == 0 && _AIVDM_buffer[i].ID == 0) {
209
_AIVDM_buffer[i] = _incoming;
210
fits_in = true;
211
break;
212
}
213
}
214
if (!fits_in) {
215
// remove the oldest message
216
#if HAL_LOGGING_ENABLED
217
if (log_unsupported) {
218
// log the unused message before removing it
219
log_raw(&_AIVDM_buffer[0]);
220
}
221
#endif
222
buffer_shift(0);
223
_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1] = _incoming;
224
}
225
}
226
}
227
}
228
229
// remove expired items from the list
230
const uint32_t now = AP_HAL::millis();
231
const uint32_t timeout = _time_out * 1000;
232
if (now < timeout) {
233
return;
234
}
235
const uint32_t deadline = now - timeout;
236
for (uint16_t i = 0; i < _list.max_items(); i++) {
237
if (_list[i].last_update_ms < deadline && _list[i].last_update_ms != 0) {
238
clear_list_item(i);
239
}
240
}
241
}
242
243
// Send a AIS mavlink message
244
void AP_AIS::send(mavlink_channel_t chan)
245
{
246
if (!enabled()) {
247
return;
248
}
249
250
const uint16_t list_size = _list.max_items();
251
const uint32_t now = AP_HAL::millis();
252
uint16_t search_length = 0;
253
while (search_length < list_size) {
254
_send_index++;
255
search_length++;
256
if (_send_index == list_size) {
257
_send_index = 0;
258
}
259
if (_list[_send_index].last_update_ms != 0 &&
260
(_list[_send_index].last_send_ms < _list[_send_index].last_update_ms || now -_list[_send_index].last_send_ms > 30000)) {
261
// only re-send if there has been a change or the resend time has expired
262
_list[_send_index].last_send_ms = now;
263
_list[_send_index].info.tslc = (now - _list[_send_index].last_update_ms) * 0.001;
264
mavlink_msg_ais_vessel_send_struct(chan,&_list[_send_index].info);
265
return;
266
}
267
}
268
}
269
270
// remove the given index from the AIVDM buffer and shift following elements up
271
void AP_AIS::buffer_shift(uint8_t i)
272
{
273
for (uint8_t n = i; n < (AIVDM_BUFFER_SIZE - 1); n++) {
274
_AIVDM_buffer[n].ID = _AIVDM_buffer[n+1].ID;
275
_AIVDM_buffer[n].num = _AIVDM_buffer[n+1].num;
276
_AIVDM_buffer[n].total = _AIVDM_buffer[n+1].total;
277
strncpy(_AIVDM_buffer[n].payload,_AIVDM_buffer[n+1].payload,AIVDM_PAYLOAD_SIZE);
278
}
279
_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1].ID = 0;
280
_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1].num = 0;
281
_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1].total = 0;
282
_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1].payload[0] = 0;
283
}
284
285
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
286
// Functions related to the vessel list
287
288
// find vessel index in existing list, if not then return NEW_NOTHROW index if possible
289
bool AP_AIS::get_vessel_index(uint32_t mmsi, uint16_t &index, uint32_t lat, uint32_t lon)
290
{
291
const uint16_t list_size = _list.max_items();
292
293
uint16_t empty = 0;
294
bool found_empty = false;
295
for (uint16_t i = 0; i < list_size; i++) {
296
if (_list[i].info.MMSI == mmsi) {
297
index = i;
298
return true;
299
}
300
if (_list[i].last_update_ms == 0 && !found_empty) {
301
found_empty = true;
302
empty = i;
303
}
304
}
305
306
// got through the list without a match
307
if (found_empty) {
308
index = empty;
309
_list[index].info.MMSI = mmsi;
310
return true;
311
}
312
313
// no space in the list
314
if (list_size < _max_list) {
315
// if we can try and expand
316
if (_list.expand(1)) {
317
index = list_size;
318
_list[index].info.MMSI = mmsi;
319
return true;
320
}
321
}
322
323
// could not expand list, either because of memory or max list param
324
// if we have a valid incoming location we can bump a further item from the list
325
if (lat == 0 && lon == 0) {
326
return false;
327
}
328
329
Location current_loc;
330
if (!AP::ahrs().get_location(current_loc)) {
331
return false;
332
}
333
334
Location loc;
335
float dist;
336
float max_dist = 0;
337
for (uint16_t i = 0; i < list_size; i++) {
338
loc.lat = _list[i].info.lat;
339
loc.lng = _list[i].info.lon;
340
dist = loc.get_distance(current_loc);
341
if (dist > max_dist) {
342
max_dist = dist;
343
index = i;
344
}
345
}
346
347
// find the current distance
348
loc.lat = lat;
349
loc.lng = lon;
350
dist = loc.get_distance(current_loc);
351
352
if (dist < max_dist) {
353
clear_list_item(index);
354
_list[index].info.MMSI = mmsi;
355
return true;
356
}
357
358
return false;
359
}
360
361
void AP_AIS::clear_list_item(uint16_t index)
362
{
363
if (index < _list.max_items()) {
364
memset(&_list[index],0,sizeof(ais_vehicle_t));
365
}
366
}
367
368
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
369
// Functions for decoding AIVDM payload messages
370
371
bool AP_AIS::payload_decode(const char *payload)
372
{
373
// the message type is defined by the first character
374
const uint8_t type = payload_char_decode(payload[0]);
375
376
switch (type) {
377
case 1: // Position Report Class A
378
case 2: // Position Report Class A (Assigned schedule)
379
case 3: // Position Report Class A (Response to interrogation)
380
return decode_position_report(payload, type);
381
case 4: // Base Station Report
382
return decode_base_station_report(payload);
383
case 5: // Static and Voyage Related Data
384
return decode_static_and_voyage_data(payload);
385
386
default:
387
return false;
388
}
389
}
390
391
bool AP_AIS::decode_position_report(const char *payload, uint8_t type)
392
{
393
if (strlen(payload) != 28) {
394
return false;
395
}
396
397
uint8_t repeat = get_bits(payload, 6, 7);
398
uint32_t mmsi = get_bits(payload, 8, 37);
399
uint8_t nav = get_bits(payload, 38, 41);
400
int8_t rot = get_bits_signed(payload, 42, 49);
401
uint16_t sog = get_bits(payload, 50, 59);
402
bool pos_acc = get_bits(payload, 60, 60);
403
int32_t lon = get_bits_signed(payload, 61, 88) * ((1.0f / 600000.0f)*1e7);
404
int32_t lat = get_bits_signed(payload, 89, 115) * ((1.0f / 600000.0f)*1e7);
405
uint16_t cog = get_bits(payload, 116, 127) * 10;
406
uint16_t head = get_bits(payload, 128, 136) * 100;
407
uint8_t sec_utc = get_bits(payload, 137, 142);
408
uint8_t maneuver = get_bits(payload, 143, 144);
409
// 145 - 147: spare
410
bool raim = get_bits(payload, 148, 148);
411
uint32_t radio = get_bits(payload, 149, 167);
412
413
#if HAL_LOGGING_ENABLED
414
// log the raw infomation
415
if ((_log_options & AIS_OPTIONS_LOG_DECODED) != 0) {
416
const struct log_AIS_msg1 pkt{
417
LOG_PACKET_HEADER_INIT(LOG_AIS_MSG1),
418
time_us : AP_HAL::micros64(),
419
type : type,
420
repeat : repeat,
421
mmsi : mmsi,
422
nav : nav,
423
rot : rot,
424
sog : sog,
425
pos_acc : pos_acc,
426
lon : lon,
427
lat : lat,
428
cog : cog,
429
head : head,
430
sec_utc : sec_utc,
431
maneuver : maneuver,
432
raim : raim,
433
radio : radio
434
};
435
AP::logger().WriteBlock(&pkt, sizeof(pkt));
436
}
437
#else
438
(void)repeat;
439
(void)nav;
440
(void)rot;
441
(void)sog;
442
(void)pos_acc;
443
(void)cog;
444
(void)head;
445
(void)sec_utc;
446
(void)maneuver;
447
(void)raim;
448
(void)radio;
449
#endif
450
451
uint16_t index;
452
if (!get_vessel_index(mmsi, index, lat, lon)) {
453
// no room in the vessel list
454
return true;
455
}
456
457
// mask of flags that we receive in this message
458
const uint16_t mask = ~(AIS_FLAGS_POSITION_ACCURACY | AIS_FLAGS_VALID_COG | AIS_FLAGS_VALID_VELOCITY | AIS_FLAGS_VALID_TURN_RATE | AIS_FLAGS_TURN_RATE_SIGN_ONLY);
459
uint16_t flags = _list[index].info.flags & mask; // clear all flags that will be updated
460
if (pos_acc) {
461
flags |= AIS_FLAGS_POSITION_ACCURACY;
462
}
463
if (cog < 36000) {
464
flags |= AIS_FLAGS_VALID_COG;
465
}
466
if (sog < 1023) {
467
flags |= AIS_FLAGS_VALID_VELOCITY;
468
}
469
if (sog == 1022) {
470
flags |= AIS_FLAGS_HIGH_VELOCITY;
471
}
472
if (rot > -128) {
473
flags |= AIS_FLAGS_VALID_TURN_RATE;
474
}
475
if (rot == 127 || rot == -127) {
476
flags |= AIS_FLAGS_TURN_RATE_SIGN_ONLY;
477
} else {
478
rot = powf((rot / 4.733f),2.0f) / 6.0f;
479
}
480
481
_list[index].info.lat = lat; // int32_t [degE7] Latitude
482
_list[index].info.lon = lon; // int32_t [degE7] Longitude
483
_list[index].info.COG = cog; // uint16_t [cdeg] Course over ground
484
_list[index].info.heading = head; // uint16_t [cdeg] True heading
485
_list[index].info.velocity = sog; // uint16_t [cm/s] Speed over ground
486
_list[index].info.flags = flags; // uint16_t Bitmask to indicate various statuses including valid data fields
487
_list[index].info.turn_rate = rot; // int8_t [cdeg/s] Turn rate
488
_list[index].info.navigational_status = nav; // uint8_t Navigational status
489
_list[index].last_update_ms = AP_HAL::millis();
490
491
return true;
492
}
493
494
bool AP_AIS::decode_base_station_report(const char *payload)
495
{
496
if (strlen(payload) != 28) {
497
return false;
498
}
499
500
uint8_t repeat = get_bits(payload, 6, 7);
501
uint32_t mmsi = get_bits(payload, 8, 37);
502
uint16_t year = get_bits(payload, 38, 51);
503
uint8_t month = get_bits(payload, 52, 55);
504
uint8_t day = get_bits(payload, 56, 60);
505
uint8_t hour = get_bits(payload, 61, 65);
506
uint8_t minute = get_bits(payload, 66, 71);
507
uint8_t second = get_bits(payload, 72, 77);
508
bool fix = get_bits(payload, 78, 78);
509
int32_t lon = get_bits_signed(payload, 79, 106) * ((1.0f / 600000.0f)*1e7);
510
int32_t lat = get_bits_signed(payload, 107, 133) * ((1.0f / 600000.0f)*1e7);
511
uint8_t epfd = get_bits(payload, 134, 137);
512
// 138 - 147: spare
513
bool raim = get_bits(payload, 148, 148);
514
uint32_t radio = get_bits(payload, 149, 167);
515
516
#if HAL_LOGGING_ENABLED
517
// log the raw infomation
518
if ((_log_options & AIS_OPTIONS_LOG_DECODED) != 0) {
519
struct log_AIS_msg4 pkt {
520
LOG_PACKET_HEADER_INIT(LOG_AIS_MSG4),
521
time_us : AP_HAL::micros64(),
522
repeat : repeat,
523
mmsi : mmsi,
524
year : year,
525
month : month,
526
day : day,
527
hour : hour,
528
minute : minute,
529
second : second,
530
fix : fix,
531
lon : lon,
532
lat : lat,
533
epfd : epfd,
534
raim : raim,
535
radio : radio
536
};
537
AP::logger().WriteBlock(&pkt, sizeof(pkt));
538
}
539
#else
540
(void)repeat;
541
(void)year;
542
(void)month;
543
(void)day;
544
(void)hour;
545
(void)minute;
546
(void)second;
547
(void)fix;
548
(void)epfd;
549
(void)raim;
550
(void)radio;
551
#endif
552
553
uint16_t index;
554
if (!get_vessel_index(mmsi, index)) {
555
return true;
556
}
557
558
_list[index].info.lat = lat; // int32_t [degE7] Latitude
559
_list[index].info.lon = lon; // int32_t [degE7] Longitude
560
_list[index].last_update_ms = AP_HAL::millis();
561
562
return true;
563
}
564
565
bool AP_AIS::decode_static_and_voyage_data(const char *payload)
566
{
567
if (strlen(payload) != 71) {
568
return false;
569
}
570
571
char call_sign[8];
572
char name[21];
573
char dest[21];
574
575
uint8_t repeat = get_bits(payload, 6, 7);
576
uint32_t mmsi = get_bits(payload, 8, 37);
577
uint8_t ver = get_bits(payload, 38, 39);
578
uint32_t imo = get_bits(payload, 40, 69);
579
get_char(payload, call_sign, 70, 111);
580
get_char(payload, name, 112, 231);
581
uint8_t vessel_type = get_bits(payload, 232, 239);
582
uint16_t bow_dim = get_bits(payload, 240, 248);
583
uint16_t stern_dim = get_bits(payload, 249, 257);
584
uint8_t port_dim = get_bits(payload, 258, 263);
585
uint8_t star_dim = get_bits(payload, 264, 269);
586
uint8_t fix = get_bits(payload, 270, 273);
587
//uint8_t month = get_bits(payload, 274, 277); // too much for a single log
588
//uint8_t day = get_bits(payload, 278, 282);
589
//uint8_t hour = get_bits(payload, 283, 287);
590
//uint8_t minute = get_bits(payload, 288, 293);
591
uint8_t draught = get_bits(payload, 294, 301);
592
get_char(payload, dest, 302, 421);
593
bool dte = get_bits(payload, 422, 422);
594
// 423 - 426: spare
595
596
#if HAL_LOGGING_ENABLED
597
// log the raw infomation
598
if ((_log_options & AIS_OPTIONS_LOG_DECODED) != 0) {
599
struct log_AIS_msg5 pkt {
600
LOG_PACKET_HEADER_INIT(LOG_AIS_MSG5),
601
time_us : AP_HAL::micros64(),
602
repeat : repeat,
603
mmsi : mmsi,
604
ver : ver,
605
imo : imo,
606
call_sign : {},
607
name : {},
608
vessel_type : vessel_type,
609
bow_dim : bow_dim,
610
stern_dim : stern_dim,
611
port_dim : port_dim,
612
star_dim : star_dim,
613
fix : fix,
614
draught : draught,
615
dest : {},
616
dte : dte
617
};
618
strncpy(pkt.call_sign, call_sign, sizeof(pkt.call_sign));
619
strncpy(pkt.name, name, sizeof(pkt.name));
620
strncpy(pkt.dest, dest, sizeof(pkt.dest));
621
AP::logger().WriteBlock(&pkt, sizeof(pkt));
622
}
623
#else
624
(void)repeat;
625
(void)ver;
626
(void)imo;
627
(void)fix;
628
(void)draught;
629
(void)dte;
630
#endif
631
632
uint16_t index;
633
if (!get_vessel_index(mmsi, index)) {
634
return true;
635
}
636
637
// mask of flags that we receive in this message
638
const uint16_t mask = ~(AIS_FLAGS_VALID_DIMENSIONS | AIS_FLAGS_LARGE_BOW_DIMENSION | AIS_FLAGS_LARGE_STERN_DIMENSION | AIS_FLAGS_LARGE_STARBOARD_DIMENSION | AIS_FLAGS_VALID_CALLSIGN | AIS_FLAGS_VALID_NAME);
639
uint16_t flags = _list[index].info.flags & mask; // clear all flags that will be updated
640
if (bow_dim != 0 && stern_dim != 0 && port_dim != 0 && star_dim != 0) {
641
flags |= AIS_FLAGS_VALID_DIMENSIONS;
642
if (bow_dim == 511) {
643
flags |= AIS_FLAGS_LARGE_BOW_DIMENSION;
644
}
645
if (stern_dim == 511) {
646
flags |= AIS_FLAGS_LARGE_STERN_DIMENSION;
647
}
648
if (port_dim == 63) {
649
flags |= AIS_FLAGS_LARGE_PORT_DIMENSION;
650
}
651
if (star_dim == 63) {
652
flags |= AIS_FLAGS_LARGE_STARBOARD_DIMENSION;
653
}
654
}
655
if (strlen(call_sign) != 0) {
656
flags |= AIS_FLAGS_VALID_CALLSIGN;
657
}
658
if (strlen(name) != 0) {
659
flags |= AIS_FLAGS_VALID_NAME;
660
}
661
662
_list[index].info.dimension_bow = bow_dim; // uint16_t [m] Distance from lat/lon location to bow
663
_list[index].info.dimension_stern = stern_dim; // uint16_t [m] Distance from lat/lon location to stern
664
_list[index].info.flags = flags; // uint16_t Bitmask to indicate various statuses including valid data fields
665
_list[index].info.type = vessel_type; // uint8_t Type of vessels
666
_list[index].info.dimension_port = port_dim; // uint8_t [m] Distance from lat/lon location to port side
667
_list[index].info.dimension_starboard = star_dim; // uint8_t [m] Distance from lat/lon location to starboard side
668
memcpy(_list[index].info.callsign,call_sign,sizeof(_list[index].info.callsign)); // char The vessel callsign
669
memcpy(_list[index].info.name,name,sizeof(_list[index].info.name)); // char The vessel name
670
671
// note that the last contact time is not updated, this message does not provide a location for a valid vessel a location must be received
672
673
return true;
674
}
675
676
677
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
678
// Functions for decoding AIVDM payload bits
679
680
// decode bits to a char array
681
void AP_AIS::get_char(const char *payload, char *array, uint16_t low, uint16_t high)
682
{
683
bool found_char = false;
684
uint8_t length = ((high - low) + 1)/6;
685
for (uint8_t i = length; i > 0; i--) {
686
uint8_t ascii = get_bits(payload, low + (i-1)*6, (low + (i*6)) - 1);
687
if (ascii < 32) {
688
ascii += 64;
689
}
690
if (ascii == 64 || (ascii == 32 && !found_char)) { // '@' marks end of string, remove trailing spaces
691
array[i-1] = 0;
692
} else {
693
found_char = true;
694
array[i-1] = ascii;
695
}
696
}
697
array[length] = 0; // always null terminate
698
}
699
700
// read the specified bits from the char array each char giving 6 bits
701
uint32_t AP_AIS::get_bits(const char *payload, uint16_t low, uint16_t high)
702
{
703
uint8_t char_low = low / 6;
704
uint8_t bit_low = low % 6;
705
706
uint8_t char_high = high / 6;
707
uint8_t bit_high = (high % 6) + 1;
708
709
uint32_t val = 0;
710
for (uint8_t index = 0; index <= char_high - char_low; index++) {
711
uint8_t value = payload_char_decode(payload[char_low + index]);
712
uint8_t mask = 0b111111;
713
if (index == 0) {
714
mask = mask >> bit_low;
715
}
716
value &= mask;
717
if (index == char_high - char_low) {
718
value = value >> (6 - bit_high);
719
val = val << bit_high;
720
} else {
721
val = val << 6;
722
}
723
724
val |= value;
725
}
726
727
return val;
728
}
729
730
// read the specified bits from the char array each char giving 6 bits
731
// As the values are a arbitrary length the sign bit is in the wrong place for standard length variables
732
int32_t AP_AIS::get_bits_signed(const char *payload, uint16_t low, uint16_t high)
733
{
734
uint32_t value = get_bits(payload, low, high);
735
if (get_bits(payload, low, low)) { // check sign bit
736
// negative number
737
return value | (UINT32_MAX << (high - low));
738
}
739
return value;
740
}
741
742
// Convert payload chars to bits
743
uint8_t AP_AIS::payload_char_decode(const char c)
744
{
745
uint8_t value = c;
746
value -= 48;
747
if (value > 40) {
748
value -= 8;
749
}
750
return value;
751
}
752
753
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
754
// Functions for decoding and logging AIVDM NMEA sentence
755
756
#if HAL_LOGGING_ENABLED
757
// log a raw AIVDM a message
758
void AP_AIS::log_raw(const AIVDM *msg)
759
{
760
struct log_AIS_raw pkt{
761
LOG_PACKET_HEADER_INIT(LOG_AIS_RAW_MSG),
762
time_us : AP_HAL::micros64(),
763
num : msg->num,
764
total : msg->total,
765
ID : msg->ID,
766
payload : {}
767
};
768
memcpy(pkt.payload, msg->payload, sizeof(pkt.payload));
769
AP::logger().WriteBlock(&pkt, sizeof(pkt));
770
}
771
#endif
772
773
// add a single character to the buffer and attempt to decode
774
// returns true if a complete sentence was successfully decoded
775
bool AP_AIS::decode(char c)
776
{
777
switch (c) {
778
case ',':
779
// end of a term, add to checksum
780
_checksum ^= c;
781
FALLTHROUGH;
782
case '\r':
783
case '\n':
784
case '*':
785
{
786
if (_sentence_done) {
787
return false;
788
}
789
790
// null terminate and decode latest term
791
_term[_term_offset] = 0;
792
bool valid_sentence = decode_latest_term();
793
794
// move onto next term
795
_term_number++;
796
_term_offset = 0;
797
_term_is_checksum = (c == '*');
798
return valid_sentence;
799
}
800
801
case '!': // sentence begin
802
_sentence_valid = false;
803
_term_number = 0;
804
_term_offset = 0;
805
_checksum = 0;
806
_term_is_checksum = false;
807
_sentence_done = false;
808
return false;
809
}
810
811
// ordinary characters are added to term
812
if (_term_offset < sizeof(_term) - 1) {
813
_term[_term_offset++] = c;
814
}
815
if (!_term_is_checksum) {
816
_checksum ^= c;
817
}
818
819
return false;
820
}
821
822
// decode the most recently consumed term
823
// returns true if new sentence has just passed checksum test and is validated
824
bool AP_AIS::decode_latest_term()
825
{
826
// handle the last term in a message
827
if (_term_is_checksum) {
828
_sentence_done = true;
829
uint8_t checksum = 16 * char_to_hex(_term[0]) + char_to_hex(_term[1]);
830
return ((checksum == _checksum) && _sentence_valid);
831
}
832
833
// the first term determines the sentence type
834
if (_term_number == 0) {
835
if (strcmp(_term, "AIVDM") == 0) {
836
// we found the sentence type for AIS
837
_sentence_valid = true;
838
}
839
return false;
840
}
841
842
// if this is not the sentence we want then wait for another
843
if (!_sentence_valid) {
844
return false;
845
}
846
847
switch (_term_number) {
848
case 1:
849
_incoming.total = strtol(_term, NULL, 10);
850
break;
851
852
case 2:
853
_incoming.num = strtol(_term, NULL, 10);
854
break;
855
856
case 3:
857
_incoming.ID = 0;
858
if (strlen(_term) > 0) {
859
_incoming.ID = strtol(_term, NULL, 10);
860
} else if (_incoming.num != 1 || _incoming.total != 1) {
861
// only allow no ID if this is a single part message
862
_sentence_valid = false;
863
}
864
break;
865
866
// case 4, chanel, either A or B, discarded
867
868
case 5:
869
if (strlen(_term) == 0) {
870
_sentence_valid = false;
871
} else {
872
strcpy(_incoming.payload,_term);
873
}
874
break;
875
876
//case 5, number of fill bits, discarded
877
}
878
return false;
879
}
880
881
// get singleton instance
882
AP_AIS *AP_AIS::get_singleton() {
883
return _singleton;
884
}
885
886
#else
887
// Dummy methods are required to allow functionality to be enabled for Rover.
888
// It is not possible to compile in or out the full code based on vehicle type due to limitations
889
// of the handling of `APM_BUILD_TYPE` define.
890
// These dummy methods minimise flash cost in that case.
891
892
const AP_Param::GroupInfo AP_AIS::var_info[] = { AP_GROUPEND };
893
AP_AIS::AP_AIS() {};
894
895
bool AP_AIS::enabled() const { return false; }
896
897
void AP_AIS::init() {};
898
void AP_AIS::update() {};
899
void AP_AIS::send(mavlink_channel_t chan) {};
900
901
AP_AIS *AP_AIS::get_singleton() { return nullptr; }
902
903
#endif // AP_AIS_DUMMY_METHODS_ENABLED
904
905
AP_AIS *AP_AIS::_singleton;
906
907
#endif // AP_AIS_ENABLED
908
909