/*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*/14#pragma once1516#include "AP_AIS_config.h"1718#if AP_AIS_ENABLED19// 0 fully disabled and compiled out20// 1 compiled in and enabled21// 2 compiled in with dummy methods, none functional, except rover which never uses dummy methods functionality2223#include <AP_Param/AP_Param.h>24#include <AP_Common/AP_ExpandingArray.h>25#include <GCS_MAVLink/GCS_MAVLink.h>2627#define AIVDM_BUFFER_SIZE 1028#define AIVDM_PAYLOAD_SIZE 652930class AP_AIS31{32public:33AP_AIS();3435CLASS_NO_COPY(AP_AIS);3637// get singleton instance38static AP_AIS *get_singleton();3940// return true if AIS is enabled41bool enabled() const;4243// Initialize the AIS object and prepare it for use44void init();4546// update AIS, expected to be called at 20hz47void update();4849// send mavlink AIS message50void send(mavlink_channel_t chan);5152// parameter block53static const struct AP_Param::GroupInfo var_info[];5455private:5657// parameters58AP_Int8 _type; // type of AIS receiver59AP_Int16 _max_list; // maximum number of vessels to track at once60AP_Int16 _time_out; // time in seconds that a vessel will be dropped from the list61AP_Int16 _log_options; // logging options bitmask6263enum class AISType {64NONE = 0,65NMEA = 1,66};6768enum options {69AIS_OPTIONS_LOG_ALL_RAW = 1<<0,70AIS_OPTIONS_LOG_UNSUPPORTED_RAW = 1<<1,71AIS_OPTIONS_LOG_DECODED = 1<<2,72};7374struct AIVDM {75uint8_t num;76uint8_t total;77uint8_t ID;78char payload[AIVDM_PAYLOAD_SIZE];79};80AIVDM _incoming;81AIVDM _AIVDM_buffer[AIVDM_BUFFER_SIZE];8283struct ais_vehicle_t {84mavlink_ais_vessel_t info;85uint32_t last_update_ms; // last time this was refreshed, allows timeouts86uint32_t last_send_ms; // last time this message was sent via mavlink, stops us spamming the link87};8889// list of the vessels that are being tracked90AP_ExpandingArray<ais_vehicle_t> _list {8};9192AP_HAL::UARTDriver *_uart;9394uint16_t _send_index; // index of the last vessel send over mavlink9596// Send a AIS vessel to the object avoidance data base if its position is valid97void send_to_object_avoidance_database(const struct ais_vehicle_t &vessel);9899// Return true if location is valid100bool check_location(int32_t lat, int32_t lng) const;101102// removed the given index from the AIVDM buffer shift following elements103void buffer_shift(uint8_t i);104105// find vessel index in existing list, if not then return new index if possible, returns true if index is valid106bool get_vessel_index(uint32_t mmsi, uint16_t &index, int32_t lat = 0, int32_t lon = 0) WARN_IF_UNUSED;107void clear_list_item(uint16_t index);108109// decode the payload110bool payload_decode(const char *payload) WARN_IF_UNUSED;111112// Apply scale to lat lon felids, avoiding integer overflow113int32_t scale_lat_lon(const int32_t val) const;114115// decode specific message types116bool decode_position_report(const char *payload, uint8_t type) WARN_IF_UNUSED;117bool decode_base_station_report(const char *payload) WARN_IF_UNUSED;118bool decode_static_and_voyage_data(const char *payload) WARN_IF_UNUSED;119120// read the specified bits from the char array each char giving 6 bits121void get_char(const char *payload, char *array, uint16_t low, uint16_t high);122uint32_t get_bits(const char *payload, uint16_t low, uint16_t high);123int32_t get_bits_signed(const char *payload, uint16_t low, uint16_t high);124// un-encode the ASCII payload armoring125uint8_t payload_char_decode(const char c);126127// log a raw AIVDM message128void log_raw(const AIVDM *msg);129130// try and decode NMEA message131bool decode(char c) WARN_IF_UNUSED;132133// decode each term134bool decode_latest_term() WARN_IF_UNUSED;135136// variables for decoding NMEA sentence137char _term[AIVDM_PAYLOAD_SIZE]; // buffer for the current term within the current sentence138uint8_t _term_offset; // offset within the _term buffer where the next character should be placed139uint8_t _term_number; // term index within the current sentence140uint8_t _checksum; // checksum accumulator141bool _term_is_checksum; // current term is the checksum142bool _sentence_valid; // is current sentence valid so far143bool _sentence_done; // true if this sentence has already been decoded144145static AP_AIS *_singleton;146};147148#endif // AP_AIS_ENABLED149150151