Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_AIS/AP_AIS.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415// Automatic Identification System, https://gpsd.gitlab.io/gpsd/AIVDM.html1617// ToDo: enable receiving of the Mavlink AIS message, type bitmask?1819#include "AP_AIS.h"2021#if AP_AIS_ENABLED2223#include <AP_Vehicle/AP_Vehicle_Type.h>2425#define AP_AIS_DUMMY_METHODS_ENABLED ((AP_AIS_ENABLED == 2) && !APM_BUILD_TYPE(APM_BUILD_Rover))2627#if !AP_AIS_DUMMY_METHODS_ENABLED2829#include <AP_Logger/AP_Logger.h>30#include <AP_SerialManager/AP_SerialManager.h>31#include <GCS_MAVLink/GCS_MAVLink.h>32#include <GCS_MAVLink/GCS.h>33#include <AP_AHRS/AP_AHRS.h>3435const AP_Param::GroupInfo AP_AIS::var_info[] = {3637// @Param: TYPE38// @DisplayName: AIS receiver type39// @Description: AIS receiver type40// @Values: 0:None,1:NMEA AIVDM message41// @User: Standard42// @RebootRequired: True43AP_GROUPINFO_FLAGS("TYPE", 1, AP_AIS, _type, 0, AP_PARAM_FLAG_ENABLE),4445// @Param: LIST_MAX46// @DisplayName: AIS vessel list size47// @Description: AIS list size of nearest vessels. Longer lists take longer to refresh with lower SRx_ADSB values.48// @Range: 1 10049// @User: Advanced50AP_GROUPINFO("LIST_MAX", 2, AP_AIS, _max_list, 25),5152// @Param: TIME_OUT53// @DisplayName: AIS vessel time out54// @Description: if no updates are received in this time a vessel will be removed from the list55// @Units: s56// @Range: 1 200057// @User: Advanced58AP_GROUPINFO("TIME_OUT", 3, AP_AIS, _time_out, 600),5960// @Param: LOGGING61// @DisplayName: AIS logging options62// @Description: Bitmask of AIS logging options63// @Bitmask: 0:Log all AIVDM messages,1:Log only unsupported AIVDM messages,2:Log decoded messages64// @User: Advanced65AP_GROUPINFO("LOGGING", 4, AP_AIS, _log_options, AIS_OPTIONS_LOG_UNSUPPORTED_RAW | AIS_OPTIONS_LOG_DECODED),6667AP_GROUPEND68};6970// constructor71AP_AIS::AP_AIS()72{73if (_singleton != nullptr) {74AP_HAL::panic("AIS must be singleton");75}76_singleton = this;7778AP_Param::setup_object_defaults(this, var_info);79}8081// return true if AIS is enabled82bool AP_AIS::enabled() const83{84return AISType(_type.get()) != AISType::NONE;85}8687// Initialize the AIS object and prepare it for use88void AP_AIS::init()89{90if (!enabled()) {91return;92}9394_uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_AIS, 0);95if (_uart == nullptr) {96return;97}9899_uart->begin(AP::serialmanager().find_baudrate(AP_SerialManager::SerialProtocol_AIS, 0));100}101102// update AIS, expected to be called at 20hz103void AP_AIS::update()104{105if (!_uart || !enabled()) {106return;107}108109// read any available lines110uint32_t nbytes = MIN(_uart->available(),1024U);111while (nbytes-- > 0) {112const int16_t byte = _uart->read();113if (byte == -1) {114break;115}116const char c = byte;117if (decode(c)) {118const bool log_all = (_log_options & AIS_OPTIONS_LOG_ALL_RAW) != 0;119const bool log_unsupported = ((_log_options & AIS_OPTIONS_LOG_UNSUPPORTED_RAW) != 0) && !log_all; // only log unsupported if not logging all120121if (_incoming.total > AIVDM_BUFFER_SIZE) {122// no point in trying to decode it wont fit123#if HAL_LOGGING_ENABLED124if (log_all || log_unsupported) {125log_raw(&_incoming);126}127#endif128break;129}130#if HAL_LOGGING_ENABLED131if (log_all) {132log_raw(&_incoming);133}134#endif135136if (_incoming.num == 1 && _incoming.total == 1) {137// single part message138if (!payload_decode(_incoming.payload) && log_unsupported) {139#if HAL_LOGGING_ENABLED140// could not decode so log141log_raw(&_incoming);142#endif143}144} else if (_incoming.num == _incoming.total) {145// last part of a multi part message146uint8_t index = 0;147uint8_t msg_parts[_incoming.num - 1];148for (uint8_t i = 0; i < AIVDM_BUFFER_SIZE; i++) {149// look for the rest of the message from the start of the buffer150// we assume the message has be received in the correct order151if (_AIVDM_buffer[i].num == (index + 1) && _AIVDM_buffer[i].total == _incoming.total && _AIVDM_buffer[i].ID == _incoming.ID) {152msg_parts[index] = i;153index++;154if (index >= _incoming.num) {155break;156}157}158}159160// did we find the right number?161if (_incoming.num != index) {162// could not find all of the message, save messages163#if HAL_LOGGING_ENABLED164if (log_unsupported) {165for (uint8_t i = 0; i < index; i++) {166log_raw(&_AIVDM_buffer[msg_parts[i]]);167}168log_raw(&_incoming);169}170#endif171// remove172for (uint8_t i = 0; i < index; i++) {173buffer_shift(msg_parts[i]);174}175break;176}177178// combine packets179char multi[AIVDM_PAYLOAD_SIZE*_incoming.total];180strncpy(multi,_AIVDM_buffer[msg_parts[0]].payload,AIVDM_PAYLOAD_SIZE);181for (uint8_t i = 1; i < _incoming.total - 1; i++) {182strncat(multi,_AIVDM_buffer[msg_parts[i]].payload,sizeof(multi));183}184strncat(multi,_incoming.payload,sizeof(multi));185#if HAL_LOGGING_ENABLED186const bool decoded = payload_decode(multi);187#endif188for (uint8_t i = 0; i < _incoming.total; i++) {189#if HAL_LOGGING_ENABLED190// unsupported type, log and discard191if (!decoded && log_unsupported) {192log_raw(&_AIVDM_buffer[msg_parts[i]]);193}194#endif195buffer_shift(msg_parts[i]);196}197#if HAL_LOGGING_ENABLED198if (!decoded && log_unsupported) {199log_raw(&_incoming);200}201#endif202} else {203// multi part message, store in buffer204bool fits_in = false;205for (uint8_t i = 0; i < AIVDM_BUFFER_SIZE; i++) {206// find the first free spot207if (_AIVDM_buffer[i].num == 0 && _AIVDM_buffer[i].total == 0 && _AIVDM_buffer[i].ID == 0) {208_AIVDM_buffer[i] = _incoming;209fits_in = true;210break;211}212}213if (!fits_in) {214// remove the oldest message215#if HAL_LOGGING_ENABLED216if (log_unsupported) {217// log the unused message before removing it218log_raw(&_AIVDM_buffer[0]);219}220#endif221buffer_shift(0);222_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1] = _incoming;223}224}225}226}227228// remove expired items from the list229const uint32_t now = AP_HAL::millis();230const uint32_t timeout = _time_out * 1000;231if (now < timeout) {232return;233}234const uint32_t deadline = now - timeout;235for (uint16_t i = 0; i < _list.max_items(); i++) {236if (_list[i].last_update_ms < deadline && _list[i].last_update_ms != 0) {237clear_list_item(i);238}239}240}241242// Send a AIS mavlink message243void AP_AIS::send(mavlink_channel_t chan)244{245if (!enabled()) {246return;247}248249const uint16_t list_size = _list.max_items();250const uint32_t now = AP_HAL::millis();251uint16_t search_length = 0;252while (search_length < list_size) {253_send_index++;254search_length++;255if (_send_index == list_size) {256_send_index = 0;257}258if (_list[_send_index].last_update_ms != 0 &&259(_list[_send_index].last_send_ms < _list[_send_index].last_update_ms || now -_list[_send_index].last_send_ms > 30000)) {260// only re-send if there has been a change or the resend time has expired261_list[_send_index].last_send_ms = now;262_list[_send_index].info.tslc = (now - _list[_send_index].last_update_ms) * 0.001;263mavlink_msg_ais_vessel_send_struct(chan,&_list[_send_index].info);264return;265}266}267}268269// remove the given index from the AIVDM buffer and shift following elements up270void AP_AIS::buffer_shift(uint8_t i)271{272for (uint8_t n = i; n < (AIVDM_BUFFER_SIZE - 1); n++) {273_AIVDM_buffer[n].ID = _AIVDM_buffer[n+1].ID;274_AIVDM_buffer[n].num = _AIVDM_buffer[n+1].num;275_AIVDM_buffer[n].total = _AIVDM_buffer[n+1].total;276strncpy(_AIVDM_buffer[n].payload,_AIVDM_buffer[n+1].payload,AIVDM_PAYLOAD_SIZE);277}278_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1].ID = 0;279_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1].num = 0;280_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1].total = 0;281_AIVDM_buffer[AIVDM_BUFFER_SIZE - 1].payload[0] = 0;282}283284//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////285// Functions related to the vessel list286287// find vessel index in existing list, if not then return NEW_NOTHROW index if possible288bool AP_AIS::get_vessel_index(uint32_t mmsi, uint16_t &index, uint32_t lat, uint32_t lon)289{290const uint16_t list_size = _list.max_items();291292uint16_t empty = 0;293bool found_empty = false;294for (uint16_t i = 0; i < list_size; i++) {295if (_list[i].info.MMSI == mmsi) {296index = i;297return true;298}299if (_list[i].last_update_ms == 0 && !found_empty) {300found_empty = true;301empty = i;302}303}304305// got through the list without a match306if (found_empty) {307index = empty;308_list[index].info.MMSI = mmsi;309return true;310}311312// no space in the list313if (list_size < _max_list) {314// if we can try and expand315if (_list.expand(1)) {316index = list_size;317_list[index].info.MMSI = mmsi;318return true;319}320}321322// could not expand list, either because of memory or max list param323// if we have a valid incoming location we can bump a further item from the list324if (lat == 0 && lon == 0) {325return false;326}327328Location current_loc;329if (!AP::ahrs().get_location(current_loc)) {330return false;331}332333Location loc;334float dist;335float max_dist = 0;336for (uint16_t i = 0; i < list_size; i++) {337loc.lat = _list[i].info.lat;338loc.lng = _list[i].info.lon;339dist = loc.get_distance(current_loc);340if (dist > max_dist) {341max_dist = dist;342index = i;343}344}345346// find the current distance347loc.lat = lat;348loc.lng = lon;349dist = loc.get_distance(current_loc);350351if (dist < max_dist) {352clear_list_item(index);353_list[index].info.MMSI = mmsi;354return true;355}356357return false;358}359360void AP_AIS::clear_list_item(uint16_t index)361{362if (index < _list.max_items()) {363memset(&_list[index],0,sizeof(ais_vehicle_t));364}365}366367//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////368// Functions for decoding AIVDM payload messages369370bool AP_AIS::payload_decode(const char *payload)371{372// the message type is defined by the first character373const uint8_t type = payload_char_decode(payload[0]);374375switch (type) {376case 1: // Position Report Class A377case 2: // Position Report Class A (Assigned schedule)378case 3: // Position Report Class A (Response to interrogation)379return decode_position_report(payload, type);380case 4: // Base Station Report381return decode_base_station_report(payload);382case 5: // Static and Voyage Related Data383return decode_static_and_voyage_data(payload);384385default:386return false;387}388}389390bool AP_AIS::decode_position_report(const char *payload, uint8_t type)391{392if (strlen(payload) != 28) {393return false;394}395396uint8_t repeat = get_bits(payload, 6, 7);397uint32_t mmsi = get_bits(payload, 8, 37);398uint8_t nav = get_bits(payload, 38, 41);399int8_t rot = get_bits_signed(payload, 42, 49);400uint16_t sog = get_bits(payload, 50, 59);401bool pos_acc = get_bits(payload, 60, 60);402int32_t lon = get_bits_signed(payload, 61, 88) * ((1.0f / 600000.0f)*1e7);403int32_t lat = get_bits_signed(payload, 89, 115) * ((1.0f / 600000.0f)*1e7);404uint16_t cog = get_bits(payload, 116, 127) * 10;405uint16_t head = get_bits(payload, 128, 136) * 100;406uint8_t sec_utc = get_bits(payload, 137, 142);407uint8_t maneuver = get_bits(payload, 143, 144);408// 145 - 147: spare409bool raim = get_bits(payload, 148, 148);410uint32_t radio = get_bits(payload, 149, 167);411412#if HAL_LOGGING_ENABLED413// log the raw infomation414if ((_log_options & AIS_OPTIONS_LOG_DECODED) != 0) {415const struct log_AIS_msg1 pkt{416LOG_PACKET_HEADER_INIT(LOG_AIS_MSG1),417time_us : AP_HAL::micros64(),418type : type,419repeat : repeat,420mmsi : mmsi,421nav : nav,422rot : rot,423sog : sog,424pos_acc : pos_acc,425lon : lon,426lat : lat,427cog : cog,428head : head,429sec_utc : sec_utc,430maneuver : maneuver,431raim : raim,432radio : radio433};434AP::logger().WriteBlock(&pkt, sizeof(pkt));435}436#else437(void)repeat;438(void)nav;439(void)rot;440(void)sog;441(void)pos_acc;442(void)cog;443(void)head;444(void)sec_utc;445(void)maneuver;446(void)raim;447(void)radio;448#endif449450uint16_t index;451if (!get_vessel_index(mmsi, index, lat, lon)) {452// no room in the vessel list453return true;454}455456// mask of flags that we receive in this message457const 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);458uint16_t flags = _list[index].info.flags & mask; // clear all flags that will be updated459if (pos_acc) {460flags |= AIS_FLAGS_POSITION_ACCURACY;461}462if (cog < 36000) {463flags |= AIS_FLAGS_VALID_COG;464}465if (sog < 1023) {466flags |= AIS_FLAGS_VALID_VELOCITY;467}468if (sog == 1022) {469flags |= AIS_FLAGS_HIGH_VELOCITY;470}471if (rot > -128) {472flags |= AIS_FLAGS_VALID_TURN_RATE;473}474if (rot == 127 || rot == -127) {475flags |= AIS_FLAGS_TURN_RATE_SIGN_ONLY;476} else {477rot = powf((rot / 4.733f),2.0f) / 6.0f;478}479480_list[index].info.lat = lat; // int32_t [degE7] Latitude481_list[index].info.lon = lon; // int32_t [degE7] Longitude482_list[index].info.COG = cog; // uint16_t [cdeg] Course over ground483_list[index].info.heading = head; // uint16_t [cdeg] True heading484_list[index].info.velocity = sog; // uint16_t [cm/s] Speed over ground485_list[index].info.flags = flags; // uint16_t Bitmask to indicate various statuses including valid data fields486_list[index].info.turn_rate = rot; // int8_t [cdeg/s] Turn rate487_list[index].info.navigational_status = nav; // uint8_t Navigational status488_list[index].last_update_ms = AP_HAL::millis();489490return true;491}492493bool AP_AIS::decode_base_station_report(const char *payload)494{495if (strlen(payload) != 28) {496return false;497}498499uint8_t repeat = get_bits(payload, 6, 7);500uint32_t mmsi = get_bits(payload, 8, 37);501uint16_t year = get_bits(payload, 38, 51);502uint8_t month = get_bits(payload, 52, 55);503uint8_t day = get_bits(payload, 56, 60);504uint8_t hour = get_bits(payload, 61, 65);505uint8_t minute = get_bits(payload, 66, 71);506uint8_t second = get_bits(payload, 72, 77);507bool fix = get_bits(payload, 78, 78);508int32_t lon = get_bits_signed(payload, 79, 106) * ((1.0f / 600000.0f)*1e7);509int32_t lat = get_bits_signed(payload, 107, 133) * ((1.0f / 600000.0f)*1e7);510uint8_t epfd = get_bits(payload, 134, 137);511// 138 - 147: spare512bool raim = get_bits(payload, 148, 148);513uint32_t radio = get_bits(payload, 149, 167);514515#if HAL_LOGGING_ENABLED516// log the raw infomation517if ((_log_options & AIS_OPTIONS_LOG_DECODED) != 0) {518struct log_AIS_msg4 pkt {519LOG_PACKET_HEADER_INIT(LOG_AIS_MSG4),520time_us : AP_HAL::micros64(),521repeat : repeat,522mmsi : mmsi,523year : year,524month : month,525day : day,526hour : hour,527minute : minute,528second : second,529fix : fix,530lon : lon,531lat : lat,532epfd : epfd,533raim : raim,534radio : radio535};536AP::logger().WriteBlock(&pkt, sizeof(pkt));537}538#else539(void)repeat;540(void)year;541(void)month;542(void)day;543(void)hour;544(void)minute;545(void)second;546(void)fix;547(void)epfd;548(void)raim;549(void)radio;550#endif551552uint16_t index;553if (!get_vessel_index(mmsi, index)) {554return true;555}556557_list[index].info.lat = lat; // int32_t [degE7] Latitude558_list[index].info.lon = lon; // int32_t [degE7] Longitude559_list[index].last_update_ms = AP_HAL::millis();560561return true;562}563564bool AP_AIS::decode_static_and_voyage_data(const char *payload)565{566if (strlen(payload) != 71) {567return false;568}569570char call_sign[8];571char name[21];572char dest[21];573574uint8_t repeat = get_bits(payload, 6, 7);575uint32_t mmsi = get_bits(payload, 8, 37);576uint8_t ver = get_bits(payload, 38, 39);577uint32_t imo = get_bits(payload, 40, 69);578get_char(payload, call_sign, 70, 111);579get_char(payload, name, 112, 231);580uint8_t vessel_type = get_bits(payload, 232, 239);581uint16_t bow_dim = get_bits(payload, 240, 248);582uint16_t stern_dim = get_bits(payload, 249, 257);583uint8_t port_dim = get_bits(payload, 258, 263);584uint8_t star_dim = get_bits(payload, 264, 269);585uint8_t fix = get_bits(payload, 270, 273);586//uint8_t month = get_bits(payload, 274, 277); // too much for a single log587//uint8_t day = get_bits(payload, 278, 282);588//uint8_t hour = get_bits(payload, 283, 287);589//uint8_t minute = get_bits(payload, 288, 293);590uint8_t draught = get_bits(payload, 294, 301);591get_char(payload, dest, 302, 421);592bool dte = get_bits(payload, 422, 422);593// 423 - 426: spare594595#if HAL_LOGGING_ENABLED596// log the raw infomation597if ((_log_options & AIS_OPTIONS_LOG_DECODED) != 0) {598struct log_AIS_msg5 pkt {599LOG_PACKET_HEADER_INIT(LOG_AIS_MSG5),600time_us : AP_HAL::micros64(),601repeat : repeat,602mmsi : mmsi,603ver : ver,604imo : imo,605call_sign : {},606name : {},607vessel_type : vessel_type,608bow_dim : bow_dim,609stern_dim : stern_dim,610port_dim : port_dim,611star_dim : star_dim,612fix : fix,613draught : draught,614dest : {},615dte : dte616};617strncpy(pkt.call_sign, call_sign, sizeof(pkt.call_sign));618strncpy(pkt.name, name, sizeof(pkt.name));619strncpy(pkt.dest, dest, sizeof(pkt.dest));620AP::logger().WriteBlock(&pkt, sizeof(pkt));621}622#else623(void)repeat;624(void)ver;625(void)imo;626(void)fix;627(void)draught;628(void)dte;629#endif630631uint16_t index;632if (!get_vessel_index(mmsi, index)) {633return true;634}635636// mask of flags that we receive in this message637const 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);638uint16_t flags = _list[index].info.flags & mask; // clear all flags that will be updated639if (bow_dim != 0 && stern_dim != 0 && port_dim != 0 && star_dim != 0) {640flags |= AIS_FLAGS_VALID_DIMENSIONS;641if (bow_dim == 511) {642flags |= AIS_FLAGS_LARGE_BOW_DIMENSION;643}644if (stern_dim == 511) {645flags |= AIS_FLAGS_LARGE_STERN_DIMENSION;646}647if (port_dim == 63) {648flags |= AIS_FLAGS_LARGE_PORT_DIMENSION;649}650if (star_dim == 63) {651flags |= AIS_FLAGS_LARGE_STARBOARD_DIMENSION;652}653}654if (strlen(call_sign) != 0) {655flags |= AIS_FLAGS_VALID_CALLSIGN;656}657if (strlen(name) != 0) {658flags |= AIS_FLAGS_VALID_NAME;659}660661_list[index].info.dimension_bow = bow_dim; // uint16_t [m] Distance from lat/lon location to bow662_list[index].info.dimension_stern = stern_dim; // uint16_t [m] Distance from lat/lon location to stern663_list[index].info.flags = flags; // uint16_t Bitmask to indicate various statuses including valid data fields664_list[index].info.type = vessel_type; // uint8_t Type of vessels665_list[index].info.dimension_port = port_dim; // uint8_t [m] Distance from lat/lon location to port side666_list[index].info.dimension_starboard = star_dim; // uint8_t [m] Distance from lat/lon location to starboard side667memcpy(_list[index].info.callsign,call_sign,sizeof(_list[index].info.callsign)); // char The vessel callsign668memcpy(_list[index].info.name,name,sizeof(_list[index].info.name)); // char The vessel name669670// note that the last contact time is not updated, this message does not provide a location for a valid vessel a location must be received671672return true;673}674675676//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////677// Functions for decoding AIVDM payload bits678679// decode bits to a char array680void AP_AIS::get_char(const char *payload, char *array, uint16_t low, uint16_t high)681{682bool found_char = false;683uint8_t length = ((high - low) + 1)/6;684for (uint8_t i = length; i > 0; i--) {685uint8_t ascii = get_bits(payload, low + (i-1)*6, (low + (i*6)) - 1);686if (ascii < 32) {687ascii += 64;688}689if (ascii == 64 || (ascii == 32 && !found_char)) { // '@' marks end of string, remove trailing spaces690array[i-1] = 0;691} else {692found_char = true;693array[i-1] = ascii;694}695}696array[length] = 0; // always null terminate697}698699// read the specified bits from the char array each char giving 6 bits700uint32_t AP_AIS::get_bits(const char *payload, uint16_t low, uint16_t high)701{702uint8_t char_low = low / 6;703uint8_t bit_low = low % 6;704705uint8_t char_high = high / 6;706uint8_t bit_high = (high % 6) + 1;707708uint32_t val = 0;709for (uint8_t index = 0; index <= char_high - char_low; index++) {710uint8_t value = payload_char_decode(payload[char_low + index]);711uint8_t mask = 0b111111;712if (index == 0) {713mask = mask >> bit_low;714}715value &= mask;716if (index == char_high - char_low) {717value = value >> (6 - bit_high);718val = val << bit_high;719} else {720val = val << 6;721}722723val |= value;724}725726return val;727}728729// read the specified bits from the char array each char giving 6 bits730// As the values are a arbitrary length the sign bit is in the wrong place for standard length variables731int32_t AP_AIS::get_bits_signed(const char *payload, uint16_t low, uint16_t high)732{733uint32_t value = get_bits(payload, low, high);734if (get_bits(payload, low, low)) { // check sign bit735// negative number736return value | (UINT32_MAX << (high - low));737}738return value;739}740741// Convert payload chars to bits742uint8_t AP_AIS::payload_char_decode(const char c)743{744uint8_t value = c;745value -= 48;746if (value > 40) {747value -= 8;748}749return value;750}751752//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////753// Functions for decoding and logging AIVDM NMEA sentence754755#if HAL_LOGGING_ENABLED756// log a raw AIVDM a message757void AP_AIS::log_raw(const AIVDM *msg)758{759struct log_AIS_raw pkt{760LOG_PACKET_HEADER_INIT(LOG_AIS_RAW_MSG),761time_us : AP_HAL::micros64(),762num : msg->num,763total : msg->total,764ID : msg->ID,765payload : {}766};767memcpy(pkt.payload, msg->payload, sizeof(pkt.payload));768AP::logger().WriteBlock(&pkt, sizeof(pkt));769}770#endif771772// add a single character to the buffer and attempt to decode773// returns true if a complete sentence was successfully decoded774bool AP_AIS::decode(char c)775{776switch (c) {777case ',':778// end of a term, add to checksum779_checksum ^= c;780FALLTHROUGH;781case '\r':782case '\n':783case '*':784{785if (_sentence_done) {786return false;787}788789// null terminate and decode latest term790_term[_term_offset] = 0;791bool valid_sentence = decode_latest_term();792793// move onto next term794_term_number++;795_term_offset = 0;796_term_is_checksum = (c == '*');797return valid_sentence;798}799800case '!': // sentence begin801_sentence_valid = false;802_term_number = 0;803_term_offset = 0;804_checksum = 0;805_term_is_checksum = false;806_sentence_done = false;807return false;808}809810// ordinary characters are added to term811if (_term_offset < sizeof(_term) - 1) {812_term[_term_offset++] = c;813}814if (!_term_is_checksum) {815_checksum ^= c;816}817818return false;819}820821// decode the most recently consumed term822// returns true if new sentence has just passed checksum test and is validated823bool AP_AIS::decode_latest_term()824{825// handle the last term in a message826if (_term_is_checksum) {827_sentence_done = true;828uint8_t checksum = 16 * char_to_hex(_term[0]) + char_to_hex(_term[1]);829return ((checksum == _checksum) && _sentence_valid);830}831832// the first term determines the sentence type833if (_term_number == 0) {834if (strcmp(_term, "AIVDM") == 0) {835// we found the sentence type for AIS836_sentence_valid = true;837}838return false;839}840841// if this is not the sentence we want then wait for another842if (!_sentence_valid) {843return false;844}845846switch (_term_number) {847case 1:848_incoming.total = strtol(_term, NULL, 10);849break;850851case 2:852_incoming.num = strtol(_term, NULL, 10);853break;854855case 3:856_incoming.ID = 0;857if (strlen(_term) > 0) {858_incoming.ID = strtol(_term, NULL, 10);859} else if (_incoming.num != 1 || _incoming.total != 1) {860// only allow no ID if this is a single part message861_sentence_valid = false;862}863break;864865// case 4, chanel, either A or B, discarded866867case 5:868if (strlen(_term) == 0) {869_sentence_valid = false;870} else {871strcpy(_incoming.payload,_term);872}873break;874875//case 5, number of fill bits, discarded876}877return false;878}879880// get singleton instance881AP_AIS *AP_AIS::get_singleton() {882return _singleton;883}884885#else886// Dummy methods are required to allow functionality to be enabled for Rover.887// It is not possible to compile in or out the full code based on vehicle type due to limitations888// of the handling of `APM_BUILD_TYPE` define.889// These dummy methods minimise flash cost in that case.890891const AP_Param::GroupInfo AP_AIS::var_info[] = { AP_GROUPEND };892AP_AIS::AP_AIS() {};893894bool AP_AIS::enabled() const { return false; }895896void AP_AIS::init() {};897void AP_AIS::update() {};898void AP_AIS::send(mavlink_channel_t chan) {};899900AP_AIS *AP_AIS::get_singleton() { return nullptr; }901902#endif // AP_AIS_DUMMY_METHODS_ENABLED903904AP_AIS *AP_AIS::_singleton;905906#endif // AP_AIS_ENABLED907908909