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.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/*16AP_ADSB.cpp1718ADS-B RF based collision avoidance module19https://en.wikipedia.org/wiki/Automatic_dependent_surveillance_%E2%80%93_broadcast20*/2122#include "AP_ADSB_config.h"2324#if HAL_ADSB_ENABLED2526#include "AP_ADSB.h"2728#include "AP_ADSB_uAvionix_MAVLink.h"29#include "AP_ADSB_uAvionix_UCP.h"30#include "AP_ADSB_Sagetech.h"31#include "AP_ADSB_Sagetech_MXS.h"3233#include <AP_AHRS/AP_AHRS.h>34#include <AP_Baro/AP_Baro.h>35#include <AP_GPS/AP_GPS.h>36#include <AP_Logger/AP_Logger.h>37#include <AP_Vehicle/AP_Vehicle_Type.h>38#include <GCS_MAVLink/GCS.h>39#include <AP_RTC/AP_RTC.h>4041#define VEHICLE_TIMEOUT_MS 5000 // if no updates in this time, drop it from the list42#define ADSB_SQUAWK_OCTAL_DEFAULT 12004344#ifndef ADSB_VEHICLE_LIST_SIZE_DEFAULT45#define ADSB_VEHICLE_LIST_SIZE_DEFAULT 2546#endif4748#ifndef ADSB_LIST_RADIUS_DEFAULT49#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)50#define ADSB_LIST_RADIUS_DEFAULT 10000 // in meters51#else52#define ADSB_LIST_RADIUS_DEFAULT 2000 // in meters53#endif54#endif5556#ifndef AP_ADSB_TYPE_DEFAULT57#define AP_ADSB_TYPE_DEFAULT 058#endif5960extern const AP_HAL::HAL& hal;6162AP_ADSB *AP_ADSB::_singleton;6364// table of user settable parameters65const AP_Param::GroupInfo AP_ADSB::var_info[] = {66// @Param: TYPE67// @DisplayName: ADSB Type68// @Description: Type of ADS-B hardware for ADSB-in and ADSB-out configuration and operation. If any type is selected then MAVLink based ADSB-in messages will always be enabled69// @Values: 0:Disabled,1:uAvionix-MAVLink,2:Sagetech,3:uAvionix-UCP,4:Sagetech MX Series70// @User: Standard71// @RebootRequired: True72AP_GROUPINFO_FLAGS("TYPE", 0, AP_ADSB, _type[0], AP_ADSB_TYPE_DEFAULT, AP_PARAM_FLAG_ENABLE),7374// index 1 is reserved - was BEHAVIOR7576// @Param: LIST_MAX77// @DisplayName: ADSB vehicle list size78// @Description: ADSB list size of nearest vehicles. Longer lists take longer to refresh with lower SRx_ADSB values.79// @Range: 1 10080// @User: Advanced81// @RebootRequired: True82AP_GROUPINFO("LIST_MAX", 2, AP_ADSB, in_state.list_size_param, ADSB_VEHICLE_LIST_SIZE_DEFAULT),838485// @Param: LIST_RADIUS86// @DisplayName: ADSB vehicle list radius filter87// @Description: ADSB vehicle list radius filter. Vehicles detected outside this radius will be completely ignored. They will not show up in the SRx_ADSB stream to the GCS and will not be considered in any avoidance calculations. A value of 0 will disable this filter.88// @Range: 0 10000089// @User: Advanced90// @Units: m91AP_GROUPINFO("LIST_RADIUS", 3, AP_ADSB, in_state.list_radius, ADSB_LIST_RADIUS_DEFAULT),9293// @Param: ICAO_ID94// @DisplayName: ICAO_ID vehicle identification number95// @Description: ICAO_ID unique vehicle identification number of this aircraft. This is an integer limited to 24bits. If set to 0 then one will be randomly generated. If set to -1 then static information is not sent, transceiver is assumed pre-programmed.96// @Range: -1 1677721597// @User: Advanced98AP_GROUPINFO("ICAO_ID", 4, AP_ADSB, out_state.cfg.ICAO_id_param, 0),99100// @Param: EMIT_TYPE101// @DisplayName: Emitter type102// @Description: ADSB classification for the type of vehicle emitting the transponder signal. Default value is 14 (UAV).103// @Values: 0:NoInfo,1:Light,2:Small,3:Large,4:HighVortexlarge,5:Heavy,6:HighlyManuv,7:Rotocraft,8:RESERVED,9:Glider,10:LightAir,11:Parachute,12:UltraLight,13:RESERVED,14:UAV,15:Space,16:RESERVED,17:EmergencySurface,18:ServiceSurface,19:PointObstacle104// @User: Advanced105AP_GROUPINFO("EMIT_TYPE", 5, AP_ADSB, out_state.cfg.emitterType, ADSB_EMITTER_TYPE_UAV),106107// @Param: LEN_WIDTH108// @DisplayName: Aircraft length and width109// @Description: Aircraft length and width dimension options in Length and Width in meters. In most cases, use a value of 1 for smallest size.110// @Values: 0:NO_DATA,1:L15W23,2:L25W28P5,3:L25W34,4:L35W33,5:L35W38,6:L45W39P5,7:L45W45,8:L55W45,9:L55W52,10:L65W59P5,11:L65W67,12:L75W72P5,13:L75W80,14:L85W80,15:L85W90111// @User: Advanced112AP_GROUPINFO("LEN_WIDTH", 6, AP_ADSB, out_state.cfg.lengthWidth, UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M),113114// @Param: OFFSET_LAT115// @DisplayName: GPS antenna lateral offset116// @Description: GPS antenna lateral offset. This describes the physical location offset from center of the GPS antenna on the aircraft.117// @Values: 0:NoData,1:Left2m,2:Left4m,3:Left6m,4:Center,5:Right2m,6:Right4m,7:Right6m118// @User: Advanced119AP_GROUPINFO("OFFSET_LAT", 7, AP_ADSB, out_state.cfg.gpsOffsetLat, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M),120121// @Param: OFFSET_LON122// @DisplayName: GPS antenna longitudinal offset123// @Description: GPS antenna longitudinal offset. This is usually set to 1, Applied By Sensor124// @Values: 0:NO_DATA,1:AppliedBySensor125// @User: Advanced126AP_GROUPINFO("OFFSET_LON", 8, AP_ADSB, out_state.cfg.gpsOffsetLon, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR),127128// @Param: RF_SELECT129// @DisplayName: Transceiver RF selection130// @Description: Transceiver RF selection for Rx enable and/or Tx enable. This only effects devices that can Tx and/or Rx. Rx-only devices should override this to always be Rx-only.131// @Bitmask: 0:Rx,1:Tx132// @User: Advanced133AP_GROUPINFO("RF_SELECT", 9, AP_ADSB, out_state.cfg.rfSelect, UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED),134135// @Param: SQUAWK136// @DisplayName: Squawk code137// @Description: VFR squawk (Mode 3/A) code is a pre-programmed default code when the pilot is flying VFR and not in contact with ATC. In the USA, the VFR squawk code is octal 1200 (hex 0x280, decimal 640) and in most parts of Europe the VFR squawk code is octal 7000. If an invalid octal number is set then it will be reset to 1200.138// @Range: 0 7777139// @Units: octal140// @User: Advanced141AP_GROUPINFO("SQUAWK", 10, AP_ADSB, out_state.cfg.squawk_octal_param, ADSB_SQUAWK_OCTAL_DEFAULT),142143// @Param: RF_CAPABLE144// @DisplayName: RF capabilities145// @Description: Describes your hardware RF In/Out capabilities.146// @Bitmask: 0:UAT_in,1:1090ES_in,2:UAT_out,3:1090ES_out147// @User: Advanced148AP_GROUPINFO("RF_CAPABLE", 11, AP_ADSB, out_state.cfg.rf_capable, 0),149150// @Param: LIST_ALT151// @DisplayName: ADSB vehicle list altitude filter152// @Description: ADSB vehicle list altitude filter. Vehicles detected above this altitude will be completely ignored. They will not show up in the SRx_ADSB stream to the GCS and will not be considered in any avoidance calculations. A value of 0 will disable this filter.153// @Range: 0 32767154// @User: Advanced155// @Units: m156AP_GROUPINFO("LIST_ALT", 12, AP_ADSB, in_state.list_altitude, 0),157158// @Param: ICAO_SPECL159// @DisplayName: ICAO_ID of special vehicle160// @Description: ICAO_ID of special vehicle that ignores ADSB_LIST_RADIUS and ADSB_LIST_ALT. The vehicle is always tracked. Use 0 to disable.161// @User: Advanced162AP_GROUPINFO("ICAO_SPECL", 13, AP_ADSB, _special_ICAO_target, 0),163164// @Param: LOG165// @DisplayName: ADS-B logging166// @Description: 0: no logging, 1: log only special ID, 2:log all167// @Values: 0:no logging,1:log only special ID,2:log all168// @User: Advanced169AP_GROUPINFO("LOG", 14, AP_ADSB, _log, 1),170171// @Param: OPTIONS172// @DisplayName: ADS-B Options173// @Description: Options for emergency failsafe codes and device capabilities174// @Bitmask: 0:Ping200X Send GPS,1:Squawk 7400 on RC failsafe,2:Squawk 7400 on GCS failsafe,3:Sagetech MXS use External Config,4:Transmit in traditional Mode 3A/C only and inhibit Mode-S and ES (ADSB) transmissions175// @User: Advanced176AP_GROUPINFO("OPTIONS", 15, AP_ADSB, _options, 0),177178AP_GROUPEND179};180181// constructor182AP_ADSB::AP_ADSB()183{184AP_Param::setup_object_defaults(this, var_info);185#if CONFIG_HAL_BOARD == HAL_BOARD_SITL186if (_singleton != nullptr) {187AP_HAL::panic("AP_ADSB must be singleton");188}189#endif190_singleton = this;191192#ifdef ADSB_STATIC_CALLSIGN193strncpy(out_state.cfg.callsign, ADSB_STATIC_CALLSIGN, sizeof(out_state.cfg.callsign));194#endif195}196197/*198* Initialize variables and allocate memory for array199*/200void AP_ADSB::init(void)201{202if (in_state.vehicle_list == nullptr) {203// sanity check param204in_state.list_size_param.set(constrain_int16(in_state.list_size_param, 1, INT16_MAX));205206in_state.vehicle_list = NEW_NOTHROW adsb_vehicle_t[in_state.list_size_param];207208if (in_state.vehicle_list == nullptr) {209// dynamic RAM allocation of in_state.vehicle_list[] failed210_init_failed = true; // this keeps us from constantly trying to init forever in main update211GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Unable to initialize ADSB vehicle list");212return;213}214in_state.list_size_allocated = in_state.list_size_param;215}216217if (detected_num_instances == 0) {218for (uint8_t i=0; i<ADSB_MAX_INSTANCES; i++) {219detect_instance(i);220if (_backend[i] == nullptr) {221continue;222}223if (!_backend[i]->init()) {224delete _backend[i];225_backend[i] = nullptr;226continue;227}228// success229detected_num_instances = i+1;230}231}232233if (detected_num_instances == 0) {234_init_failed = true;235GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB: Unable to initialize ADSB driver");236}237}238239bool AP_ADSB::check_startup()240{241if (_init_failed) {242return false;243}244245bool all_backends_disabled = true;246for (uint8_t instance=0; instance<ADSB_MAX_INSTANCES; instance++) {247if (_type[instance] > 0) {248all_backends_disabled = false;249break;250}251}252253if (all_backends_disabled) {254// nothing to do255return false;256}257if (in_state.vehicle_list == nullptr) {258init();259}260return in_state.vehicle_list != nullptr;261}262263264// detect if an instance of an ADSB sensor is connected.265void AP_ADSB::detect_instance(uint8_t instance)266{267switch (get_type(instance)) {268case Type::None:269return;270271case Type::uAvionix_MAVLink:272#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED273if (AP_ADSB_uAvionix_MAVLink::detect()) {274_backend[instance] = NEW_NOTHROW AP_ADSB_uAvionix_MAVLink(*this, instance);275}276#endif277break;278279case Type::uAvionix_UCP:280#if HAL_ADSB_UCP_ENABLED281if (AP_ADSB_uAvionix_UCP::detect()) {282_backend[instance] = NEW_NOTHROW AP_ADSB_uAvionix_UCP(*this, instance);283}284#endif285break;286287case Type::Sagetech:288#if HAL_ADSB_SAGETECH_ENABLED289if (AP_ADSB_Sagetech::detect()) {290_backend[instance] = NEW_NOTHROW AP_ADSB_Sagetech(*this, instance);291}292#endif293break;294295case Type::Sagetech_MXS:296#if HAL_ADSB_SAGETECH_MXS_ENABLED297if (AP_ADSB_Sagetech_MXS::detect()) {298_backend[instance] = NEW_NOTHROW AP_ADSB_Sagetech_MXS(*this, instance);299}300#endif301break;302}303304}305306// get instance type from instance307AP_ADSB::Type AP_ADSB::get_type(uint8_t instance) const308{309if (instance < ADSB_MAX_INSTANCES) {310return (Type)(_type[instance].get());311}312return Type::None;313}314315bool AP_ADSB::is_valid_callsign(uint16_t octal)316{317// treat "octal" as decimal and test if any decimal digit is > 7318if (octal > 7777) {319return false;320}321322while (octal != 0) {323if (octal % 10 > 7) {324return false;325}326octal /= 10;327}328329return true;330}331332#if AP_GPS_ENABLED && AP_AHRS_ENABLED && AP_BARO_ENABLED333/*334* periodic update to handle vehicle timeouts and trigger collision detection335*/336void AP_ADSB::update(void)337{338Loc loc{};339if (!AP::ahrs().get_location(loc)) {340loc.zero();341}342343const AP_GPS &gps = AP::gps();344345loc.fix_type = (AP_GPS_FixType)gps.status();346loc.epoch_us = gps.time_epoch_usec();347#if AP_RTC_ENABLED348loc.have_epoch_from_rtc_us = AP::rtc().get_utc_usec(loc.epoch_from_rtc_us);349#endif350351loc.satellites = gps.num_sats();352353loc.horizontal_pos_accuracy_is_valid = gps.horizontal_accuracy(loc.horizontal_pos_accuracy);354loc.vertical_pos_accuracy_is_valid = gps.vertical_accuracy(loc.vertical_pos_accuracy);355loc.horizontal_vel_accuracy_is_valid = gps.speed_accuracy(loc.horizontal_vel_accuracy);356357358loc.vel_ned = gps.velocity();359360loc.vertRateD_is_valid = AP::ahrs().get_vert_pos_rate_D(loc.vertRateD);361362const auto &baro = AP::baro();363loc.baro_is_healthy = baro.healthy();364365// Altitude difference between sea level pressure and current366// pressure (in metres)367if (loc.baro_is_healthy) {368loc.baro_alt_press_diff_sea_level = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure());369}370371update(loc);372}373#endif // AP_GPS_ENABLED && AP_AHRS_ENABLED374375void AP_ADSB::update(const AP_ADSB::Loc &loc)376{377if (!check_startup()) {378return;379}380381_my_loc = loc;382383const uint32_t now = AP_HAL::millis();384385// check current list for vehicles that time out386uint16_t index = 0;387while (index < in_state.vehicle_count) {388// check list and drop stale vehicles. When disabled, the list will get flushed389if (now - in_state.vehicle_list[index].last_update_ms > VEHICLE_TIMEOUT_MS) {390// don't increment index, we want to check this same index again because the contents changed391// also, if we're disabled then clear the list392delete_vehicle(index);393} else {394index++;395}396}397398if (out_state.cfg.squawk_octal_param != out_state.cfg.squawk_octal) {399// param changed, check that it's a valid octal400if (!is_valid_callsign(out_state.cfg.squawk_octal_param)) {401// invalid, reset it to default402out_state.cfg.squawk_octal_param.set(ADSB_SQUAWK_OCTAL_DEFAULT);403}404out_state.cfg.squawk_octal = (uint16_t)out_state.cfg.squawk_octal_param;405}406407// ensure it's positive 24bit but allow -1408if (out_state.cfg.ICAO_id_param <= -1 || out_state.cfg.ICAO_id_param > 0x00FFFFFF) {409// icao param of -1 means static information is not sent, transceiver is assumed pre-programmed.410// reset timer constantly so it never reaches 10s so it never sends411out_state.last_config_ms = now;412413} else if ((out_state.cfg.rfSelect & UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED) &&414(out_state.cfg.ICAO_id == 0 || out_state.cfg.ICAO_id_param_prev != out_state.cfg.ICAO_id_param)) {415416// if param changed then regenerate. This allows the param to be changed back to zero to trigger a re-generate417if (out_state.cfg.ICAO_id_param == 0) {418out_state.cfg.ICAO_id = genICAO(_my_loc);419} else {420out_state.cfg.ICAO_id = out_state.cfg.ICAO_id_param;421}422out_state.cfg.ICAO_id_param_prev = out_state.cfg.ICAO_id_param;423424#ifndef ADSB_STATIC_CALLSIGN425if (!out_state.cfg.was_set_externally) {426set_callsign("ARDU", true);427}428#endif429out_state.last_config_ms = 0; // send now430}431432for (uint8_t i=0; i<detected_num_instances; i++) {433if (_backend[i] != nullptr && _type[i].get() != (int8_t)Type::None) {434_backend[i]->update();435}436}437438}439440/*441* determine index and distance of furthest vehicle. This is442* used to bump it off when a new closer aircraft is detected443*/444void AP_ADSB::determine_furthest_aircraft(void)445{446float max_distance = 0;447uint16_t max_distance_index = 0;448449for (uint16_t index = 0; index < in_state.vehicle_count; index++) {450if (is_special_vehicle(in_state.vehicle_list[index].info.ICAO_address)) {451continue;452}453const float distance = _my_loc.get_distance(get_location(in_state.vehicle_list[index]));454if (max_distance < distance || index == 0) {455max_distance = distance;456max_distance_index = index;457}458} // for index459460in_state.furthest_vehicle_index = max_distance_index;461in_state.furthest_vehicle_distance = max_distance;462}463464/*465* Convert/Extract a Location from a vehicle466*/467Location AP_ADSB::get_location(const adsb_vehicle_t &vehicle) const468{469const Location loc = Location(470vehicle.info.lat,471vehicle.info.lon,472vehicle.info.altitude * 0.1f,473Location::AltFrame::ABSOLUTE);474475return loc;476}477478/*479* delete a vehicle by copying last vehicle to480* current index then decrementing count481*/482void AP_ADSB::delete_vehicle(const uint16_t index)483{484if (index >= in_state.vehicle_count) {485// index out of range486return;487}488489// if the vehicle is the furthest, invalidate it. It has been bumped490if (index == in_state.furthest_vehicle_index && in_state.furthest_vehicle_distance > 0) {491in_state.furthest_vehicle_distance = 0;492in_state.furthest_vehicle_index = 0;493}494if (index != (in_state.vehicle_count-1)) {495in_state.vehicle_list[index] = in_state.vehicle_list[in_state.vehicle_count-1];496}497// TODO: is memset needed? When we decrement the index we essentially forget about it498memset(&in_state.vehicle_list[in_state.vehicle_count-1], 0, sizeof(adsb_vehicle_t));499in_state.vehicle_count--;500}501502/*503* Search _vehicle_list for the given vehicle. A match504* depends on ICAO_address. Returns true if match found505* and index is populated. otherwise, return false.506*/507bool AP_ADSB::find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const508{509for (uint16_t i = 0; i < in_state.vehicle_count; i++) {510if (in_state.vehicle_list[i].info.ICAO_address == vehicle.info.ICAO_address) {511*index = i;512return true;513}514}515return false;516}517518/*519* Update the vehicle list. If the vehicle is already in the520* list then it will update it, otherwise it will be added.521*/522void AP_ADSB::handle_adsb_vehicle(const adsb_vehicle_t &vehicle)523{524if (!check_startup()) {525return;526}527528uint16_t index = in_state.list_size_allocated + 1; // initialize with invalid index529const Location vehicle_loc = AP_ADSB::get_location(vehicle);530const bool my_loc_is_zero = _my_loc.is_zero();531const float my_loc_distance_to_vehicle = _my_loc.get_distance(vehicle_loc);532const bool is_special = is_special_vehicle(vehicle.info.ICAO_address);533const bool out_of_range = in_state.list_radius > 0 && !my_loc_is_zero && my_loc_distance_to_vehicle > in_state.list_radius && !is_special;534const bool out_of_range_alt = in_state.list_altitude > 0 && !my_loc_is_zero && abs(vehicle_loc.alt - _my_loc.alt) > in_state.list_altitude*100 && !is_special;535const bool is_tracked_in_list = find_index(vehicle, &index);536const uint32_t now = AP_HAL::millis();537538const uint16_t required_flags_position = ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE;539const bool detected_ourself = (out_state.cfg.ICAO_id != 0) && ((uint32_t)out_state.cfg.ICAO_id == vehicle.info.ICAO_address);540541if (vehicle_loc.is_zero() ||542out_of_range ||543out_of_range_alt ||544detected_ourself ||545(vehicle.info.ICAO_address > 0x00FFFFFF) || // ICAO address is 24bits, so ignore higher values.546!(vehicle.info.flags & required_flags_position) ||547now - vehicle.last_update_ms > VEHICLE_TIMEOUT_MS) {548549// vehicle is out of range or invalid lat/lng. If we're tracking it, delete from list. Otherwise ignore it.550if (is_tracked_in_list) {551delete_vehicle(index);552}553return;554555} else if (is_tracked_in_list) {556557// found, update it558set_vehicle(index, vehicle);559560} else if (in_state.vehicle_count < in_state.list_size_allocated) {561562// not found and there's room, add it to the end of the list563set_vehicle(in_state.vehicle_count, vehicle);564in_state.vehicle_count++;565566} else {567// buffer is full. if new vehicle is closer than furthest, replace furthest with new568569if (my_loc_is_zero) {570// nothing else to do571in_state.furthest_vehicle_distance = 0;572in_state.furthest_vehicle_index = 0;573574} else {575if (in_state.furthest_vehicle_distance <= 0) {576// ensure this is populated577determine_furthest_aircraft();578}579580if (my_loc_distance_to_vehicle < in_state.furthest_vehicle_distance) { // is closer than the furthest581// replace with the furthest vehicle582set_vehicle(in_state.furthest_vehicle_index, vehicle);583584// in_state.furthest_vehicle_index is now invalid because the vehicle was overwritten, need585// to run determine_furthest_aircraft() to determine a new one next time586in_state.furthest_vehicle_distance = 0;587in_state.furthest_vehicle_index = 0;588}589}590} // if buffer full591592const uint16_t required_flags_avoidance =593ADSB_FLAGS_VALID_COORDS |594ADSB_FLAGS_VALID_ALTITUDE |595ADSB_FLAGS_VALID_HEADING |596ADSB_FLAGS_VALID_VELOCITY;597598if (vehicle.info.flags & required_flags_avoidance) {599push_sample(vehicle); // note that set_vehicle modifies vehicle600}601}602603/*604* Copy a vehicle's data into the list605*/606void AP_ADSB::set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle)607{608if (index >= in_state.list_size_allocated) {609// out of range610return;611}612in_state.vehicle_list[index] = vehicle;613614#if HAL_LOGGING_ENABLED615write_log(vehicle);616#endif617}618619void AP_ADSB::send_adsb_vehicle(const mavlink_channel_t chan)620{621if (!check_startup() || in_state.vehicle_count == 0) {622return;623}624625uint32_t now = AP_HAL::millis();626627if (in_state.send_index[chan] >= in_state.vehicle_count) {628// we've finished a list629if (now - in_state.send_start_ms[chan] < 1000) {630// too soon to start a new one631return;632} else {633// start new list634in_state.send_start_ms[chan] = now;635in_state.send_index[chan] = 0;636}637}638639if (in_state.send_index[chan] < in_state.vehicle_count) {640mavlink_adsb_vehicle_t vehicle = in_state.vehicle_list[in_state.send_index[chan]].info;641in_state.send_index[chan]++;642643mavlink_msg_adsb_vehicle_send(chan,644vehicle.ICAO_address,645vehicle.lat,646vehicle.lon,647vehicle.altitude_type,648vehicle.altitude,649vehicle.heading,650vehicle.hor_velocity,651vehicle.ver_velocity,652vehicle.callsign,653vehicle.emitter_type,654vehicle.tslc,655vehicle.flags,656vehicle.squawk);657}658}659660/*661* handle incoming packet UAVIONIX_ADSB_OUT_CFG.662* This allows a GCS to send cfg info through the autopilot to the ADSB hardware.663* This is done indirectly by reading and storing the packet and then another mechanism sends it out periodically664*/665void AP_ADSB::handle_out_cfg(const mavlink_uavionix_adsb_out_cfg_t &packet)666{667out_state.cfg.was_set_externally = true;668669out_state.cfg.ICAO_id = packet.ICAO;670out_state.cfg.ICAO_id_param.set(out_state.cfg.ICAO_id_param_prev = packet.ICAO & 0x00FFFFFFFF);671672// May contain a non-null value at the end so accept it as-is with memcpy instead of strcpy673memcpy(out_state.cfg.callsign, packet.callsign, sizeof(out_state.cfg.callsign));674675out_state.cfg.emitterType.set(packet.emitterType);676out_state.cfg.lengthWidth.set(packet.aircraftSize);677out_state.cfg.gpsOffsetLat.set(packet.gpsOffsetLat);678out_state.cfg.gpsOffsetLon.set(packet.gpsOffsetLon);679out_state.cfg.rfSelect.set(packet.rfSelect);680out_state.cfg.stall_speed_cm = packet.stallSpeed;681682// guard against string with non-null end char683char tmp_callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN+1] {};684memcpy(tmp_callsign, out_state.cfg.callsign, MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN);685GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, tmp_callsign);686687// send now688out_state.last_config_ms = 0;689}690691/*692* handle incoming packet UAVIONIX_ADSB_OUT_CONTROL693* allows a GCS to set the contents of the control message sent by ardupilot to the transponder694*/695void AP_ADSB::handle_out_control(const mavlink_uavionix_adsb_out_control_t &packet)696{697out_state.ctrl.baroCrossChecked = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED;698out_state.ctrl.airGroundState = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND;699out_state.ctrl.modeAEnabled = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED;700out_state.ctrl.modeCEnabled = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED;701out_state.ctrl.modeSEnabled = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED;702out_state.ctrl.es1090TxEnabled = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED;703out_state.ctrl.externalBaroAltitude_mm = packet.baroAltMSL;704out_state.ctrl.squawkCode = packet.squawk;705out_state.ctrl.emergencyState = packet.emergencyStatus;706memcpy(out_state.ctrl.callsign, packet.flight_id, sizeof(out_state.ctrl.callsign));707out_state.ctrl.x_bit = packet.x_bit;708709if (packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE) {710IGNORE_RETURN(ident_start());711}712}713714/*715* this is a message from the transceiver reporting it's health. Using this packet716* we determine which channel is on so we don't have to send out_state to all channels717*/718void AP_ADSB::handle_transceiver_report(const mavlink_channel_t chan, const mavlink_uavionix_adsb_transceiver_health_report_t &packet)719{720if (out_state.chan != chan) {721GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "ADSB: Found transceiver on channel %d", chan);722}723724out_state.chan_last_ms = AP_HAL::millis();725out_state.chan = chan;726out_state.status = (UAVIONIX_ADSB_RF_HEALTH)packet.rfHealth;727}728729/*730* send a periodic report of the ADSB out status731*/732void AP_ADSB::send_adsb_out_status(const mavlink_channel_t chan) const733{734for (uint8_t i=0; i < ADSB_MAX_INSTANCES; i++) {735if (_type[i] == (int8_t)(AP_ADSB::Type::uAvionix_UCP) || _type[i] == (int8_t)(AP_ADSB::Type::Sagetech_MXS)) {736mavlink_msg_uavionix_adsb_out_status_send_struct(chan, &out_state.tx_status);737return;738}739}740}741742/*743@brief Generates pseudorandom ICAO from gps time, lat, and lon.744Reference: DO282B, 2.2.4.5.1.3.2745*/746uint32_t AP_ADSB::genICAO(const Location &loc) const747{748// gps_time is used as a pseudo-random number instead of seconds since UTC midnight749// TODO: use UTC time instead of GPS time750const AP_ADSB::Loc &gps { _my_loc };751const uint64_t gps_time = gps.time_epoch_usec();752753uint32_t timeSum = 0;754const uint32_t M3 = 4096 * (loc.lat & 0x00000FFF) + (loc.lng & 0x00000FFF);755756for (uint8_t i=0; i<24; i++) {757timeSum += (((gps_time & 0x00FFFFFF)>> i) & 0x00000001);758}759return( (timeSum ^ M3) & 0x00FFFFFF);760}761762// assign a string to out_state.cfg.callsign but ensure it's null terminated763void AP_ADSB::set_callsign(const char* str, const bool append_icao)764{765bool zero_char_pad = false;766767// clean slate768memset(out_state.cfg.callsign, 0, sizeof(out_state.cfg.callsign));769770// copy str to cfg.callsign but we can't use strncpy because we need771// to restrict values to only 'A' - 'Z' and '0' - '9' and pad772for (uint8_t i=0; i<sizeof(out_state.cfg.callsign)-1; i++) {773if (!str[i] || zero_char_pad) {774// finish early. Either pad the rest with zero char or null terminate and call it a day775if ((append_icao && i<4) || zero_char_pad) {776out_state.cfg.callsign[i] = '0';777zero_char_pad = true;778} else {779// already null terminated via memset so just stop780break;781}782783} else if (('A' <= str[i] && str[i] <= 'Z') ||784('0' <= str[i] && str[i] <= '9')) {785// valid as-is786// spaces are also allowed but are handled in the last else787out_state.cfg.callsign[i] = str[i];788789} else if ('a' <= str[i] && str[i] <= 'z') {790// toupper()791out_state.cfg.callsign[i] = str[i] - ('a' - 'A');792793} else if (i == 0) {794// invalid, pad to char zero because first index can't be space795out_state.cfg.callsign[i] = '0';796797} else {798// invalid, pad with space799out_state.cfg.callsign[i] = ' ';800}801} // for i802803if (append_icao) {804hal.util->snprintf(&out_state.cfg.callsign[4], 5, "%04X", unsigned(out_state.cfg.ICAO_id % 0x10000));805}806}807808809void AP_ADSB::push_sample(const adsb_vehicle_t &vehicle)810{811_samples.push(vehicle);812}813814bool AP_ADSB::next_sample(adsb_vehicle_t &vehicle)815{816return _samples.pop(vehicle);817}818819void AP_ADSB::handle_message(const mavlink_channel_t chan, const mavlink_message_t &msg)820{821switch (msg.msgid) {822case MAVLINK_MSG_ID_ADSB_VEHICLE: {823adsb_vehicle_t vehicle {};824mavlink_msg_adsb_vehicle_decode(&msg, &vehicle.info);825vehicle.last_update_ms = AP_HAL::millis() - uint32_t(vehicle.info.tslc * 1000U);826handle_adsb_vehicle(vehicle);827break;828}829830case MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT: {831mavlink_uavionix_adsb_transceiver_health_report_t packet {};832mavlink_msg_uavionix_adsb_transceiver_health_report_decode(&msg, &packet);833handle_transceiver_report(chan, packet);834break;835}836837case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG: {838mavlink_uavionix_adsb_out_cfg_t packet {};839mavlink_msg_uavionix_adsb_out_cfg_decode(&msg, &packet);840handle_out_cfg(packet);841break;842}843844case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC:845// unhandled, this is an outbound packet only846break;847848case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL: {849mavlink_uavionix_adsb_out_control_t packet {};850mavlink_msg_uavionix_adsb_out_control_decode(&msg, &packet);851handle_out_control(packet);852break;853}854}855856}857858// If that ICAO is found in the database then return true with a fully populated vehicle859bool AP_ADSB::get_vehicle_by_ICAO(const uint32_t icao, adsb_vehicle_t &vehicle) const860{861adsb_vehicle_t temp_vehicle;862temp_vehicle.info.ICAO_address = icao;863864uint16_t i;865if (find_index(temp_vehicle, &i)) {866// vehicle is tracked in list.867// we must memcpy it because the database may reorganize itself and we don't868// want the reference to magically start pointing at a different vehicle869memcpy(&vehicle, &in_state.vehicle_list[i], sizeof(adsb_vehicle_t));870return true;871}872return false;873}874875#if HAL_LOGGING_ENABLED876/*877* Write vehicle to log878*/879void AP_ADSB::write_log(const adsb_vehicle_t &vehicle) const880{881switch ((Logging)_log) {882case Logging::SPECIAL_ONLY:883if (!is_special_vehicle(vehicle.info.ICAO_address)) {884return;885}886break;887888case Logging::ALL:889break;890891case Logging::NONE:892default:893return;894}895896struct log_ADSB pkt = {897LOG_PACKET_HEADER_INIT(LOG_ADSB_MSG),898time_us : AP_HAL::micros64(),899ICAO_address : vehicle.info.ICAO_address,900lat : vehicle.info.lat,901lng : vehicle.info.lon,902alt : vehicle.info.altitude,903heading : vehicle.info.heading,904hor_velocity : vehicle.info.hor_velocity,905ver_velocity : vehicle.info.ver_velocity,906squawk : vehicle.info.squawk,907};908AP::logger().WriteBlock(&pkt, sizeof(pkt));909}910#endif // HAL_LOGGING_ENABLED911912/**913* @brief Convert base 8 or 16 to decimal. Used to convert an octal/hexadecimal value stored on a GCS as a string field in different format, but then transmitted over mavlink as a float which is always a decimal.914* baseIn: base of input number915* inputNumber: value currently in base "baseIn" to be converted to base "baseOut"916*917* Example: convert ADSB squawk octal "1200" stored in memory as 0x0280 to 0x04B0918* uint16_t squawk_decimal = convertMathBase(8, squawk_octal);919*/920uint32_t AP_ADSB::convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber)921{922// Our only sensible input bases are 16 and 8923if (baseIn != 8 && baseIn != 16) {924return inputNumber;925}926uint32_t outputNumber = 0;927for (uint8_t i=0; i < 10; i++) {928outputNumber += (inputNumber % 10) * powf(baseIn, i);929inputNumber /= 10;930if (inputNumber == 0) break;931}932return outputNumber;933}934935// Trigger a Mode 3/A transponder IDENT. This should only be done when requested to do so by an Air Traffic Controller.936// See wikipedia for IDENT explanation https://en.wikipedia.org/wiki/Transponder_(aeronautics)937bool AP_ADSB::ident_start()938{939if (!healthy()) {940return false;941}942out_state.ctrl.identActive = true;943GCS_SEND_TEXT(MAV_SEVERITY_INFO,"ADSB: IDENT!");944return true;945}946947// methods for embedded class Location948bool AP_ADSB::Loc::speed_accuracy(float &sacc) const949{950if (!horizontal_vel_accuracy_is_valid) {951return false;952}953sacc = horizontal_vel_accuracy;954return true;955}956957bool AP_ADSB::Loc::horizontal_accuracy(float &hacc) const958{959if (!horizontal_pos_accuracy_is_valid) {960return false;961}962hacc = horizontal_pos_accuracy;963return true;964}965966bool AP_ADSB::Loc::vertical_accuracy(float &vacc) const967{968if (!vertical_pos_accuracy_is_valid) {969return false;970}971vacc = vertical_pos_accuracy;972return true;973}974975uint8_t AP_ADSB::convert_maxknots_to_enum(const float maxAircraftSpeed_knots)976{977if (maxAircraftSpeed_knots <= 0) {978// not set or unknown. no bits set979return 0;980} else if (maxAircraftSpeed_knots <= 75) {981return 1;982} else if (maxAircraftSpeed_knots <= 150) {983return 2;984} else if (maxAircraftSpeed_knots <= 300) {985return 3;986} else if (maxAircraftSpeed_knots <= 600) {987return 4;988} else if (maxAircraftSpeed_knots <= 1200) {989return 5;990} else {991return 6;992}993}994995AP_ADSB *AP::ADSB()996{997return AP_ADSB::get_singleton();998}999#endif // HAL_ADSB_ENABLED100010011002