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