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_ADSB/AP_ADSB_Sagetech.cpp
Views: 1798
/*1Copyright (C) 2020 Kraus Hamdani Aerospace Inc. All rights reserved.23This program is free software: you can redistribute it and/or modify4it under the terms of the GNU General Public License as published by5the Free Software Foundation, either version 3 of the License, or6(at your option) any later version.78This program is distributed in the hope that it will be useful,9but WITHOUT ANY WARRANTY; without even the implied warranty of10MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the11GNU General Public License for more details.1213You should have received a copy of the GNU General Public License14along with this program. If not, see <http://www.gnu.org/licenses/>.15*/1617#include "AP_ADSB_Sagetech.h"1819#if HAL_ADSB_SAGETECH_ENABLED20#include <GCS_MAVLink/GCS.h>21#include <AP_SerialManager/AP_SerialManager.h>22#include <AP_HAL/utility/sparse-endian.h>23#include <stdio.h>24#include <time.h>25#include <string.h>26#include <math.h>2728#define SAGETECH_SCALER_LATLNG (1.0f/2.145767E-5f) // 180/(2^23)29#define SAGETECH_SCALER_KNOTS_TO_CMS ((KNOTS_TO_M_PER_SEC/0.125f) * 100.0f)30#define SAGETECH_SCALER_ALTITUDE (1.0f/0.015625f)31#define SAGETECH_SCALER_HEADING_CM ((360.0f/256.0f) * 100.0f)3233#define SAGETECH_VALIDFLAG_LATLNG (1U<<0)34#define SAGETECH_VALIDFLAG_ALTITUDE (1U<<1)35#define SAGETECH_VALIDFLAG_VELOCITY (1U<<2)36#define SAGETECH_VALIDFLAG_GND_SPEED (1U<<3)37#define SAGETECH_VALIDFLAG_HEADING (1U<<4)38#define SAGETECH_VALIDFLAG_V_RATE_GEO (1U<<5)39#define SAGETECH_VALIDFLAG_V_RATE_BARO (1U<<6)40#define SAGETECH_VALIDFLAG_EST_LATLNG (1U<<7)41#define SAGETECH_VALIDFLAG_EST_VELOCITY (1U<<8)4243// detect if any port is configured as Sagetech44bool AP_ADSB_Sagetech::detect()45{46return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_ADSB, 0);47}4849// Init, called once after class is constructed50bool AP_ADSB_Sagetech::init()51{52_port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_ADSB, 0);5354return (_port != nullptr);55}5657void AP_ADSB_Sagetech::update()58{59if (_port == nullptr) {60return;61}6263const uint32_t now_ms = AP_HAL::millis();6465// -----------------------------66// read any available data on serial port67// -----------------------------68uint32_t nbytes = MIN(_port->available(), 10 * PAYLOAD_XP_MAX_SIZE);69while (nbytes-- > 0) {70uint8_t data;71if (!_port->read(data)) {72break;73}74if (parse_byte_XP(data)) {75handle_packet_XP(message_in.packet);76}77} // while nbytes787980// -----------------------------81// handle timers for generating data82// -----------------------------83if (!last_packet_initialize_ms || (now_ms - last_packet_initialize_ms >= 5000)) {84last_packet_initialize_ms = now_ms;85send_packet(MsgType_XP::Installation_Set);8687} else if (!last_packet_PreFlight_ms || (now_ms - last_packet_PreFlight_ms >= 8200)) {88last_packet_PreFlight_ms = now_ms;89// TODO: allow callsign to not require a reboot90send_packet(MsgType_XP::Preflight_Set);9192} else if (now_ms - last_packet_Operating_ms >= 1000 && (93last_packet_Operating_ms == 0 || // send once at boot94// send as data changes95last_operating_squawk != _frontend.out_state.cfg.squawk_octal ||96abs(last_operating_alt - _frontend._my_loc.alt) > 1555 || // 1493cm == 49ft. The output resolution is 100ft per bit97last_operating_rf_select != _frontend.out_state.cfg.rfSelect))98{99last_packet_Operating_ms = now_ms;100last_operating_squawk = _frontend.out_state.cfg.squawk_octal;101last_operating_alt = _frontend._my_loc.alt;102last_operating_rf_select = _frontend.out_state.cfg.rfSelect;103send_packet(MsgType_XP::Operating_Set);104105} else if (now_ms - last_packet_GPS_ms >= (_frontend.out_state.is_flying ? 200 : 1000)) {106// 1Hz when not flying, 5Hz when flying107last_packet_GPS_ms = now_ms;108send_packet(MsgType_XP::GPS_Set);109}110}111112void AP_ADSB_Sagetech::send_packet(const MsgType_XP type)113{114switch (type) {115case MsgType_XP::Installation_Set:116send_msg_Installation();117break;118case MsgType_XP::Preflight_Set:119send_msg_PreFlight();120break;121case MsgType_XP::Operating_Set:122send_msg_Operating();123break;124case MsgType_XP::GPS_Set:125send_msg_GPS();126break;127default:128break;129}130}131132void AP_ADSB_Sagetech::request_packet(const MsgType_XP type)133{134// set all bytes in packet to 0 via {} so we only need to set the ones we need to135Packet_XP pkt {};136137pkt.type = MsgType_XP::Request;138pkt.id = 0;139pkt.payload_length = 4;140141pkt.payload[0] = static_cast<uint8_t>(type);142143send_msg(pkt);144}145146147void AP_ADSB_Sagetech::handle_packet_XP(const Packet_XP &msg)148{149switch (msg.type) {150case MsgType_XP::ACK:151handle_ack(msg);152break;153154case MsgType_XP::Installation_Response:155case MsgType_XP::Preflight_Response:156case MsgType_XP::Status_Response:157// TODO add support for these158break;159160case MsgType_XP::ADSB_StateVector_Report:161case MsgType_XP::ADSB_ModeStatus_Report:162case MsgType_XP::TISB_StateVector_Report:163case MsgType_XP::TISB_ModeStatus_Report:164case MsgType_XP::TISB_CorasePos_Report:165case MsgType_XP::TISB_ADSB_Mgr_Report:166handle_adsb_in_msg(msg);167break;168169case MsgType_XP::Installation_Set:170case MsgType_XP::Preflight_Set:171case MsgType_XP::Operating_Set:172case MsgType_XP::GPS_Set:173case MsgType_XP::Request:174// these are out-bound only and are not expected to be received175case MsgType_XP::INVALID:176break;177}178}179180void AP_ADSB_Sagetech::handle_ack(const Packet_XP &msg)181{182// ACK received!183const uint8_t system_state = msg.payload[2];184transponder_type = (Transponder_Type)msg.payload[6];185186const uint8_t prev_transponder_mode = last_ack_transponder_mode;187last_ack_transponder_mode = (system_state >> 6) & 0x03;188if (prev_transponder_mode != last_ack_transponder_mode) {189static const char *mode_names[] = {"OFF", "STBY", "ON", "ON-ALT"};190if (last_ack_transponder_mode < ARRAY_SIZE(mode_names)) {191GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: RF Mode: %s", mode_names[last_ack_transponder_mode]);192}193}194}195196void AP_ADSB_Sagetech::handle_adsb_in_msg(const Packet_XP &msg)197{198AP_ADSB::adsb_vehicle_t vehicle {};199200vehicle.last_update_ms = AP_HAL::millis();201202switch (msg.type) {203case MsgType_XP::ADSB_StateVector_Report: { // 0x91204const uint16_t validFlags = le16toh_ptr(&msg.payload[8]);205vehicle.info.ICAO_address = le24toh_ptr(&msg.payload[10]);206207if (validFlags & SAGETECH_VALIDFLAG_LATLNG) {208vehicle.info.lat = ((int32_t)le24toh_ptr(&msg.payload[20])) * SAGETECH_SCALER_LATLNG;209vehicle.info.lon = ((int32_t)le24toh_ptr(&msg.payload[23])) * SAGETECH_SCALER_LATLNG;210vehicle.info.flags |= ADSB_FLAGS_VALID_COORDS;211}212213if (validFlags & SAGETECH_VALIDFLAG_ALTITUDE) {214vehicle.info.altitude = (int32_t)le24toh_ptr(&msg.payload[26]);215vehicle.info.flags |= ADSB_FLAGS_VALID_ALTITUDE;216}217218if (validFlags & SAGETECH_VALIDFLAG_VELOCITY) {219const float velNS = ((int32_t)le16toh_ptr(&msg.payload[29])) * SAGETECH_SCALER_KNOTS_TO_CMS;220const float velEW = ((int32_t)le16toh_ptr(&msg.payload[31])) * SAGETECH_SCALER_KNOTS_TO_CMS;221vehicle.info.hor_velocity = Vector2f(velEW, velNS).length();222vehicle.info.flags |= ADSB_FLAGS_VALID_VELOCITY;223}224225if (validFlags & SAGETECH_VALIDFLAG_HEADING) {226vehicle.info.heading = ((float)msg.payload[29]) * SAGETECH_SCALER_HEADING_CM;227vehicle.info.flags |= ADSB_FLAGS_VALID_HEADING;228}229230if ((validFlags & SAGETECH_VALIDFLAG_V_RATE_GEO) || (validFlags & SAGETECH_VALIDFLAG_V_RATE_BARO)) {231vehicle.info.ver_velocity = (int16_t)le16toh_ptr(&msg.payload[38]);232vehicle.info.flags |= ADSB_FLAGS_VERTICAL_VELOCITY_VALID;233}234235_frontend.handle_adsb_vehicle(vehicle);236break;237}238case MsgType_XP::ADSB_ModeStatus_Report: // 0x92239vehicle.info.ICAO_address = le24toh_ptr(&msg.payload[9]);240241if (msg.payload[16] != 0) {242// if string is non-null, consider it valid243memcpy(&vehicle.info, &msg.payload[16], 8);244vehicle.info.flags |= ADSB_FLAGS_VALID_CALLSIGN;245}246247_frontend.handle_adsb_vehicle(vehicle);248break;249case MsgType_XP::TISB_StateVector_Report:250case MsgType_XP::TISB_ModeStatus_Report:251case MsgType_XP::TISB_CorasePos_Report:252case MsgType_XP::TISB_ADSB_Mgr_Report:253// TODO254return;255256default:257return;258}259260}261262// handling inbound byte and process it in the state machine263// return true when a full packet has been received264bool AP_ADSB_Sagetech::parse_byte_XP(const uint8_t data)265{266switch (message_in.state) {267default:268case ParseState::WaitingFor_Start:269if (data == 0xA5) {270message_in.state = ParseState::WaitingFor_AssmAddr;271}272break;273case ParseState::WaitingFor_AssmAddr:274message_in.state = (data == 0x01) ? ParseState::WaitingFor_MsgType : ParseState::WaitingFor_Start;275break;276case ParseState::WaitingFor_MsgType:277message_in.packet.type = static_cast<MsgType_XP>(data);278message_in.state = ParseState::WaitingFor_MsgId;279break;280case ParseState::WaitingFor_MsgId:281message_in.packet.id = data;282message_in.state = ParseState::WaitingFor_PayloadLen;283break;284case ParseState::WaitingFor_PayloadLen:285message_in.packet.payload_length = data;286message_in.index = 0;287message_in.state = (data == 0) ? ParseState::WaitingFor_ChecksumFletcher : ParseState::WaitingFor_PayloadContents;288break;289290case ParseState::WaitingFor_PayloadContents:291message_in.packet.payload[message_in.index++] = data;292if (message_in.index >= message_in.packet.payload_length) {293message_in.state = ParseState::WaitingFor_ChecksumFletcher;294message_in.index = 0;295}296break;297298case ParseState::WaitingFor_ChecksumFletcher:299message_in.packet.checksumFletcher = data;300message_in.state = ParseState::WaitingFor_Checksum;301break;302case ParseState::WaitingFor_Checksum:303message_in.packet.checksum = data;304message_in.state = ParseState::WaitingFor_End;305if (checksum_verify_XP(message_in.packet)) {306handle_packet_XP(message_in.packet);307}308break;309310case ParseState::WaitingFor_End:311// we don't care if the end value matches312message_in.state = ParseState::WaitingFor_Start;313break;314}315return false;316}317318// compute Sum and FletcherSum values into a single value319// returns uint16_t with MSByte as Sum and LSByte FletcherSum320uint16_t AP_ADSB_Sagetech::checksum_generate_XP(Packet_XP &msg) const321{322uint8_t sum = 0;323uint8_t sumFletcher = 0;324325const uint8_t header_message_format[5] {3260xA5, // start3270x01, // assembly address328static_cast<uint8_t>(msg.type),329msg.id,330msg.payload_length331};332333for (uint8_t i=0; i<5; i++) {334sum += header_message_format[i];335sumFletcher += sum;336}337for (uint8_t i=0; i<msg.payload_length; i++) {338sum += msg.payload[i];339sumFletcher += sum;340}341342return UINT16_VALUE(sum, sumFletcher);343}344345// computes checksum and returns true if it matches msg checksum346bool AP_ADSB_Sagetech::checksum_verify_XP(Packet_XP &msg) const347{348const uint16_t checksum = checksum_generate_XP(msg);349return (HIGHBYTE(checksum) == msg.checksum) && (LOWBYTE(checksum) == msg.checksumFletcher);350}351352// computes checksum and assigns checksum values to msg353void AP_ADSB_Sagetech::checksum_assign_XP(Packet_XP &msg)354{355const uint16_t checksum = checksum_generate_XP(msg);356msg.checksum = HIGHBYTE(checksum);357msg.checksumFletcher = LOWBYTE(checksum);358}359360// send message to serial port361void AP_ADSB_Sagetech::send_msg(Packet_XP &msg)362{363// generate and populate checksums.364checksum_assign_XP(msg);365366const uint8_t message_format_header[5] {3670xA5, // start3680x01, // assembly address369static_cast<uint8_t>(msg.type),370msg.id,371msg.payload_length372};373const uint8_t message_format_tail[3] {374msg.checksumFletcher,375msg.checksum,3760x5A // end377};378379if (_port != nullptr) {380_port->write(message_format_header, sizeof(message_format_header));381_port->write(msg.payload, msg.payload_length);382_port->write(message_format_tail, sizeof(message_format_tail));383}384}385386void AP_ADSB_Sagetech::send_msg_Installation()387{388Packet_XP pkt {};389390pkt.type = MsgType_XP::Installation_Set;391pkt.payload_length = 28; // 28== 0x1C392393// Mode C = 3, Mode S = 0394pkt.id = (transponder_type == Transponder_Type::Mode_C) ? 3 : 0;395396// // convert a decimal 123456 to 0x123456397// TODO: do a proper conversion. The param contains "131313" but what gets transmitted over the air is 0x200F1.398const uint32_t icao_hex = AP_ADSB::convert_base_to_decimal(16, _frontend.out_state.cfg.ICAO_id_param);399put_le24_ptr(&pkt.payload[0], icao_hex);400401memcpy(&pkt.payload[3], &_frontend.out_state.cfg.callsign, 8);402403pkt.payload[11] = 0; // airspeed MAX404405pkt.payload[12] = 0; // COM Port 0 baud, fixed at 57600406pkt.payload[13] = 0; // COM Port 1 baud, fixed at 57600407pkt.payload[14] = 0; // COM Port 2 baud, fixed at 57600408409pkt.payload[15] = 1; // GPS from COM port 0 (this port)410pkt.payload[16] = 1; // GPS Integrity411412pkt.payload[17] = _frontend.out_state.cfg.emitterType / 8; // Emitter Set413pkt.payload[18] = _frontend.out_state.cfg.emitterType & 0x0F; // Emitter Type414415pkt.payload[19] = _frontend.out_state.cfg.lengthWidth; // Aircraft Size416417pkt.payload[20] = 0; // Altitude Encoder Offset418pkt.payload[21] = 0; // Altitude Encoder Offset419420pkt.payload[22] = 0x07; // ADSB In Control, enable reading everything421pkt.payload[23] = 30; // ADSB In Report max length COM Port 0 (this one)422pkt.payload[24] = 0; // ADSB In Report max length COM Port 1423424send_msg(pkt);425}426427void AP_ADSB_Sagetech::send_msg_PreFlight()428{429Packet_XP pkt {};430431pkt.type = MsgType_XP::Preflight_Set;432pkt.id = 0;433pkt.payload_length = 10;434435memcpy(&pkt.payload[0], &_frontend.out_state.cfg.callsign, 8);436437memset(&pkt.payload[8], 0, 2);438439send_msg(pkt);440}441442void AP_ADSB_Sagetech::send_msg_Operating()443{444Packet_XP pkt {};445446pkt.type = MsgType_XP::Operating_Set;447pkt.id = 0;448pkt.payload_length = 8;449450// squawk451// param is saved as native octal so we need convert back to452// decimal because Sagetech will convert it back to octal453const uint16_t squawk = AP_ADSB::convert_base_to_decimal(8, last_operating_squawk);454put_le16_ptr(&pkt.payload[0], squawk);455456// altitude457if (_frontend.out_state.cfg.rf_capable & 0x01) {458const float alt_meters = last_operating_alt * 0.01f;459const int32_t alt_feet = (int32_t)(alt_meters * FEET_TO_METERS);460const int16_t alt_feet_adj = (alt_feet + 50) / 100; // 1 = 100 feet, 1 = 149 feet, 5 = 500 feet461put_le16_ptr(&pkt.payload[2], alt_feet_adj);462463} else {464// use integrated altitude - recommend by sagetech465pkt.payload[2] = 0x80;466pkt.payload[3] = 0x00;467}468469// RF mode470pkt.payload[4] = last_operating_rf_select;471send_msg(pkt);472}473474void AP_ADSB_Sagetech::send_msg_GPS()475{476Packet_XP pkt {};477478pkt.type = MsgType_XP::GPS_Set;479pkt.payload_length = 52;480pkt.id = 0;481482const auto &loc = _frontend._my_loc;483484const int32_t longitude = loc.lng;485const int32_t latitude = loc.lat;486487// longitude and latitude488// NOTE: these MUST be done in double or else we get roundoff in the maths489const double lon_deg = longitude * (double)1.0e-7 * (longitude < 0 ? -1 : 1);490const double lon_minutes = (lon_deg - int(lon_deg)) * 60;491snprintf((char*)&pkt.payload[0], 12, "%03u%02u.%05u", (unsigned)lon_deg, (unsigned)lon_minutes, unsigned((lon_minutes - (int)lon_minutes) * 1.0E5));492493const double lat_deg = latitude * (double)1.0e-7 * (latitude < 0 ? -1 : 1);494const double lat_minutes = (lat_deg - int(lat_deg)) * 60;495snprintf((char*)&pkt.payload[11], 11, "%02u%02u.%05u", (unsigned)lat_deg, (unsigned)lat_minutes, unsigned((lat_minutes - (int)lat_minutes) * 1.0E5));496497// ground speed498const Vector2f speed = loc.groundspeed_vector();499float speed_knots = speed.length() * M_PER_SEC_TO_KNOTS;500snprintf((char*)&pkt.payload[21], 7, "%03u.%02u", (unsigned)speed_knots, unsigned((speed_knots - (int)speed_knots) * 1.0E2));501502// heading503float heading = wrap_360(degrees(speed.angle()));504snprintf((char*)&pkt.payload[27], 10, "%03u.%04u", unsigned(heading), unsigned((heading - (int)heading) * 1.0E4));505506// hemisphere507uint8_t hemisphere = 0;508hemisphere |= (latitude >= 0) ? 0x01 : 0; // isNorth509hemisphere |= (longitude >= 0) ? 0x02 : 0; // isEast510hemisphere |= (loc.status() < AP_GPS_FixType::FIX_2D) ? 0x80 : 0; // isInvalid511pkt.payload[35] = hemisphere;512513// time514uint64_t time_usec = loc.epoch_from_rtc_us;515if (loc.have_epoch_from_rtc_us) {516// not completely accurate, our time includes leap seconds and time_t should be without517const time_t time_sec = time_usec / 1000000;518struct tm tmd {};519struct tm* tm = gmtime_r(&time_sec, &tmd);520521// format time string522snprintf((char*)&pkt.payload[36], 11, "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6);523} else {524memset(&pkt.payload[36],' ', 10);525}526527send_msg(pkt);528}529530#endif // HAL_ADSB_SAGETECH_ENABLED531532533534