#include "AP_ADSB_config.h"
#if HAL_ADSB_ENABLED
#include "AP_ADSB.h"
#include "AP_ADSB_uAvionix_MAVLink.h"
#include "AP_ADSB_uAvionix_UCP.h"
#include "AP_ADSB_Sagetech.h"
#include "AP_ADSB_Sagetech_MXS.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_RTC/AP_RTC.h>
#define VEHICLE_TIMEOUT_MS 5000
#define ADSB_SQUAWK_OCTAL_DEFAULT 1200
#ifndef ADSB_VEHICLE_LIST_SIZE_DEFAULT
#define ADSB_VEHICLE_LIST_SIZE_DEFAULT 25
#endif
#ifndef ADSB_LIST_RADIUS_DEFAULT
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
#define ADSB_LIST_RADIUS_DEFAULT 10000
#else
#define ADSB_LIST_RADIUS_DEFAULT 2000
#endif
#endif
#ifndef AP_ADSB_TYPE_DEFAULT
#define AP_ADSB_TYPE_DEFAULT 0
#endif
extern const AP_HAL::HAL& hal;
AP_ADSB *AP_ADSB::_singleton;
const AP_Param::GroupInfo AP_ADSB::var_info[] = {
AP_GROUPINFO_FLAGS("TYPE", 0, AP_ADSB, _type[0], AP_ADSB_TYPE_DEFAULT, AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO("LIST_MAX", 2, AP_ADSB, in_state.list_size_param, ADSB_VEHICLE_LIST_SIZE_DEFAULT),
AP_GROUPINFO("LIST_RADIUS", 3, AP_ADSB, in_state.list_radius, ADSB_LIST_RADIUS_DEFAULT),
AP_GROUPINFO("ICAO_ID", 4, AP_ADSB, out_state.cfg.ICAO_id_param, 0),
AP_GROUPINFO("EMIT_TYPE", 5, AP_ADSB, out_state.cfg.emitterType, ADSB_EMITTER_TYPE_UAV),
AP_GROUPINFO("LEN_WIDTH", 6, AP_ADSB, out_state.cfg.lengthWidth, UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M),
AP_GROUPINFO("OFFSET_LAT", 7, AP_ADSB, out_state.cfg.gpsOffsetLat, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M),
AP_GROUPINFO("OFFSET_LON", 8, AP_ADSB, out_state.cfg.gpsOffsetLon, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR),
AP_GROUPINFO("RF_SELECT", 9, AP_ADSB, out_state.cfg.rfSelect, UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED),
AP_GROUPINFO("SQUAWK", 10, AP_ADSB, out_state.cfg.squawk_octal_param, ADSB_SQUAWK_OCTAL_DEFAULT),
AP_GROUPINFO("RF_CAPABLE", 11, AP_ADSB, out_state.cfg.rf_capable, 0),
AP_GROUPINFO("LIST_ALT", 12, AP_ADSB, in_state.list_altitude, 0),
AP_GROUPINFO("ICAO_SPECL", 13, AP_ADSB, _special_ICAO_target, 0),
AP_GROUPINFO("LOG", 14, AP_ADSB, _log, 1),
AP_GROUPINFO("OPTIONS", 15, AP_ADSB, _options, 0),
AP_GROUPEND
};
AP_ADSB::AP_ADSB()
{
AP_Param::setup_object_defaults(this, var_info);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (_singleton != nullptr) {
AP_HAL::panic("AP_ADSB must be singleton");
}
#endif
_singleton = this;
#ifdef ADSB_STATIC_CALLSIGN
strncpy(out_state.cfg.callsign, ADSB_STATIC_CALLSIGN, sizeof(out_state.cfg.callsign));
#endif
}
void AP_ADSB::init(void)
{
if (in_state.vehicle_list == nullptr) {
in_state.list_size_param.set(constrain_int16(in_state.list_size_param, 1, INT16_MAX));
in_state.vehicle_list = NEW_NOTHROW adsb_vehicle_t[in_state.list_size_param];
if (in_state.vehicle_list == nullptr) {
_init_failed = true;
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Unable to initialize ADSB vehicle list");
return;
}
in_state.list_size_allocated = in_state.list_size_param;
}
if (detected_num_instances == 0) {
for (uint8_t i=0; i<ADSB_MAX_INSTANCES; i++) {
detect_instance(i);
if (_backend[i] == nullptr) {
continue;
}
if (!_backend[i]->init()) {
delete _backend[i];
_backend[i] = nullptr;
continue;
}
detected_num_instances = i+1;
}
}
if (detected_num_instances == 0) {
_init_failed = true;
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB: Unable to initialize ADSB driver");
}
}
bool AP_ADSB::check_startup()
{
if (_init_failed) {
return false;
}
bool all_backends_disabled = true;
for (uint8_t instance=0; instance<ADSB_MAX_INSTANCES; instance++) {
if (_type[instance] > 0) {
all_backends_disabled = false;
break;
}
}
if (all_backends_disabled) {
return false;
}
if (in_state.vehicle_list == nullptr) {
init();
}
return in_state.vehicle_list != nullptr;
}
void AP_ADSB::detect_instance(uint8_t instance)
{
switch (get_type(instance)) {
case Type::None:
return;
case Type::uAvionix_MAVLink:
#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED
if (AP_ADSB_uAvionix_MAVLink::detect()) {
_backend[instance] = NEW_NOTHROW AP_ADSB_uAvionix_MAVLink(*this, instance);
}
#endif
break;
case Type::uAvionix_UCP:
#if HAL_ADSB_UCP_ENABLED
if (AP_ADSB_uAvionix_UCP::detect()) {
_backend[instance] = NEW_NOTHROW AP_ADSB_uAvionix_UCP(*this, instance);
}
#endif
break;
case Type::Sagetech:
#if HAL_ADSB_SAGETECH_ENABLED
if (AP_ADSB_Sagetech::detect()) {
_backend[instance] = NEW_NOTHROW AP_ADSB_Sagetech(*this, instance);
}
#endif
break;
case Type::Sagetech_MXS:
#if HAL_ADSB_SAGETECH_MXS_ENABLED
if (AP_ADSB_Sagetech_MXS::detect()) {
_backend[instance] = NEW_NOTHROW AP_ADSB_Sagetech_MXS(*this, instance);
}
#endif
break;
}
}
AP_ADSB::Type AP_ADSB::get_type(uint8_t instance) const
{
if (instance < ADSB_MAX_INSTANCES) {
return (Type)(_type[instance].get());
}
return Type::None;
}
bool AP_ADSB::is_valid_callsign(uint16_t octal)
{
if (octal > 7777) {
return false;
}
while (octal != 0) {
if (octal % 10 > 7) {
return false;
}
octal /= 10;
}
return true;
}
#if AP_GPS_ENABLED && AP_AHRS_ENABLED && AP_BARO_ENABLED
void AP_ADSB::update(void)
{
Loc loc{};
if (!AP::ahrs().get_location(loc)) {
loc.zero();
}
const AP_GPS &gps = AP::gps();
loc.fix_type = (AP_GPS_FixType)gps.status();
loc.epoch_us = gps.time_epoch_usec();
#if AP_RTC_ENABLED
loc.have_epoch_from_rtc_us = AP::rtc().get_utc_usec(loc.epoch_from_rtc_us);
#endif
loc.satellites = gps.num_sats();
loc.horizontal_pos_accuracy_is_valid = gps.horizontal_accuracy(loc.horizontal_pos_accuracy);
loc.vertical_pos_accuracy_is_valid = gps.vertical_accuracy(loc.vertical_pos_accuracy);
loc.horizontal_vel_accuracy_is_valid = gps.speed_accuracy(loc.horizontal_vel_accuracy);
loc.vel_ned = gps.velocity();
loc.vertRateD_is_valid = AP::ahrs().get_vert_pos_rate_D(loc.vertRateD);
const auto &baro = AP::baro();
loc.baro_is_healthy = baro.healthy();
if (loc.baro_is_healthy) {
loc.baro_alt_press_diff_sea_level = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure());
}
update(loc);
}
#endif
void AP_ADSB::update(const AP_ADSB::Loc &loc)
{
if (!check_startup()) {
return;
}
_my_loc = loc;
const uint32_t now = AP_HAL::millis();
uint16_t index = 0;
while (index < in_state.vehicle_count) {
if (now - in_state.vehicle_list[index].last_update_ms > VEHICLE_TIMEOUT_MS) {
delete_vehicle(index);
} else {
index++;
}
}
if (out_state.cfg.squawk_octal_param != out_state.cfg.squawk_octal) {
if (!is_valid_callsign(out_state.cfg.squawk_octal_param)) {
out_state.cfg.squawk_octal_param.set(ADSB_SQUAWK_OCTAL_DEFAULT);
}
out_state.cfg.squawk_octal = (uint16_t)out_state.cfg.squawk_octal_param;
}
if (out_state.cfg.ICAO_id_param <= -1 || out_state.cfg.ICAO_id_param > 0x00FFFFFF) {
out_state.last_config_ms = now;
} else if ((out_state.cfg.rfSelect & UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED) &&
(out_state.cfg.ICAO_id == 0 || out_state.cfg.ICAO_id_param_prev != out_state.cfg.ICAO_id_param)) {
if (out_state.cfg.ICAO_id_param == 0) {
out_state.cfg.ICAO_id = genICAO(_my_loc);
} else {
out_state.cfg.ICAO_id = out_state.cfg.ICAO_id_param;
}
out_state.cfg.ICAO_id_param_prev = out_state.cfg.ICAO_id_param;
#ifndef ADSB_STATIC_CALLSIGN
if (!out_state.cfg.was_set_externally) {
set_callsign("ARDU", true);
}
#endif
out_state.last_config_ms = 0;
}
for (uint8_t i=0; i<detected_num_instances; i++) {
if (_backend[i] != nullptr && _type[i].get() != (int8_t)Type::None) {
_backend[i]->update();
}
}
}
void AP_ADSB::determine_furthest_aircraft(void)
{
float max_distance = 0;
uint16_t max_distance_index = 0;
for (uint16_t index = 0; index < in_state.vehicle_count; index++) {
if (is_special_vehicle(in_state.vehicle_list[index].info.ICAO_address)) {
continue;
}
const float distance = _my_loc.get_distance(get_location(in_state.vehicle_list[index]));
if (max_distance < distance || index == 0) {
max_distance = distance;
max_distance_index = index;
}
}
in_state.furthest_vehicle_index = max_distance_index;
in_state.furthest_vehicle_distance = max_distance;
}
Location AP_ADSB::get_location(const adsb_vehicle_t &vehicle) const
{
const Location loc = Location(
vehicle.info.lat,
vehicle.info.lon,
vehicle.info.altitude * 0.1f,
Location::AltFrame::ABSOLUTE);
return loc;
}
void AP_ADSB::delete_vehicle(const uint16_t index)
{
if (index >= in_state.vehicle_count) {
return;
}
if (index == in_state.furthest_vehicle_index && in_state.furthest_vehicle_distance > 0) {
in_state.furthest_vehicle_distance = 0;
in_state.furthest_vehicle_index = 0;
}
if (index != (in_state.vehicle_count-1)) {
in_state.vehicle_list[index] = in_state.vehicle_list[in_state.vehicle_count-1];
}
memset(&in_state.vehicle_list[in_state.vehicle_count-1], 0, sizeof(adsb_vehicle_t));
in_state.vehicle_count--;
}
bool AP_ADSB::find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const
{
for (uint16_t i = 0; i < in_state.vehicle_count; i++) {
if (in_state.vehicle_list[i].info.ICAO_address == vehicle.info.ICAO_address) {
*index = i;
return true;
}
}
return false;
}
void AP_ADSB::handle_adsb_vehicle(const adsb_vehicle_t &vehicle)
{
if (!check_startup()) {
return;
}
uint16_t index = in_state.list_size_allocated + 1;
const Location vehicle_loc = AP_ADSB::get_location(vehicle);
const bool my_loc_is_zero = _my_loc.is_zero();
const float my_loc_distance_to_vehicle = _my_loc.get_distance(vehicle_loc);
const bool is_special = is_special_vehicle(vehicle.info.ICAO_address);
const bool out_of_range = in_state.list_radius > 0 && !my_loc_is_zero && my_loc_distance_to_vehicle > in_state.list_radius && !is_special;
const 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;
const bool is_tracked_in_list = find_index(vehicle, &index);
const uint32_t now = AP_HAL::millis();
const uint16_t required_flags_position = ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE;
const bool detected_ourself = (out_state.cfg.ICAO_id != 0) && ((uint32_t)out_state.cfg.ICAO_id == vehicle.info.ICAO_address);
if (vehicle_loc.is_zero() ||
out_of_range ||
out_of_range_alt ||
detected_ourself ||
(vehicle.info.ICAO_address > 0x00FFFFFF) ||
!(vehicle.info.flags & required_flags_position) ||
now - vehicle.last_update_ms > VEHICLE_TIMEOUT_MS) {
if (is_tracked_in_list) {
delete_vehicle(index);
}
return;
} else if (is_tracked_in_list) {
set_vehicle(index, vehicle);
} else if (in_state.vehicle_count < in_state.list_size_allocated) {
set_vehicle(in_state.vehicle_count, vehicle);
in_state.vehicle_count++;
} else {
if (my_loc_is_zero) {
in_state.furthest_vehicle_distance = 0;
in_state.furthest_vehicle_index = 0;
} else {
if (in_state.furthest_vehicle_distance <= 0) {
determine_furthest_aircraft();
}
if (my_loc_distance_to_vehicle < in_state.furthest_vehicle_distance) {
set_vehicle(in_state.furthest_vehicle_index, vehicle);
in_state.furthest_vehicle_distance = 0;
in_state.furthest_vehicle_index = 0;
}
}
}
const uint16_t required_flags_avoidance =
ADSB_FLAGS_VALID_COORDS |
ADSB_FLAGS_VALID_ALTITUDE |
ADSB_FLAGS_VALID_HEADING |
ADSB_FLAGS_VALID_VELOCITY;
if (vehicle.info.flags & required_flags_avoidance) {
push_sample(vehicle);
}
}
void AP_ADSB::set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle)
{
if (index >= in_state.list_size_allocated) {
return;
}
in_state.vehicle_list[index] = vehicle;
#if HAL_LOGGING_ENABLED
write_log(vehicle);
#endif
}
void AP_ADSB::send_adsb_vehicle(const mavlink_channel_t chan)
{
if (!check_startup() || in_state.vehicle_count == 0) {
return;
}
uint32_t now = AP_HAL::millis();
if (in_state.send_index[chan] >= in_state.vehicle_count) {
if (now - in_state.send_start_ms[chan] < 1000) {
return;
} else {
in_state.send_start_ms[chan] = now;
in_state.send_index[chan] = 0;
}
}
if (in_state.send_index[chan] < in_state.vehicle_count) {
mavlink_adsb_vehicle_t vehicle = in_state.vehicle_list[in_state.send_index[chan]].info;
in_state.send_index[chan]++;
mavlink_msg_adsb_vehicle_send(chan,
vehicle.ICAO_address,
vehicle.lat,
vehicle.lon,
vehicle.altitude_type,
vehicle.altitude,
vehicle.heading,
vehicle.hor_velocity,
vehicle.ver_velocity,
vehicle.callsign,
vehicle.emitter_type,
vehicle.tslc,
vehicle.flags,
vehicle.squawk);
}
}
void AP_ADSB::handle_out_cfg(const mavlink_uavionix_adsb_out_cfg_t &packet)
{
out_state.cfg.was_set_externally = true;
out_state.cfg.ICAO_id = packet.ICAO;
out_state.cfg.ICAO_id_param.set(out_state.cfg.ICAO_id_param_prev = packet.ICAO & 0x00FFFFFFFF);
memcpy(out_state.cfg.callsign, packet.callsign, sizeof(out_state.cfg.callsign));
out_state.cfg.emitterType.set(packet.emitterType);
out_state.cfg.lengthWidth.set(packet.aircraftSize);
out_state.cfg.gpsOffsetLat.set(packet.gpsOffsetLat);
out_state.cfg.gpsOffsetLon.set(packet.gpsOffsetLon);
out_state.cfg.rfSelect.set(packet.rfSelect);
out_state.cfg.stall_speed_cm = packet.stallSpeed;
char tmp_callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN+1] {};
memcpy(tmp_callsign, out_state.cfg.callsign, MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, tmp_callsign);
out_state.last_config_ms = 0;
}
void AP_ADSB::handle_out_control(const mavlink_uavionix_adsb_out_control_t &packet)
{
out_state.ctrl.baroCrossChecked = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED;
out_state.ctrl.airGroundState = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND;
out_state.ctrl.modeAEnabled = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED;
out_state.ctrl.modeCEnabled = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED;
out_state.ctrl.modeSEnabled = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED;
out_state.ctrl.es1090TxEnabled = packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED;
out_state.ctrl.externalBaroAltitude_mm = packet.baroAltMSL;
out_state.ctrl.squawkCode = packet.squawk;
out_state.ctrl.emergencyState = packet.emergencyStatus;
memcpy(out_state.ctrl.callsign, packet.flight_id, sizeof(out_state.ctrl.callsign));
out_state.ctrl.x_bit = packet.x_bit;
if (packet.state & UAVIONIX_ADSB_OUT_CONTROL_STATE::UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE) {
IGNORE_RETURN(ident_start());
}
}
void AP_ADSB::handle_transceiver_report(const mavlink_channel_t chan, const mavlink_uavionix_adsb_transceiver_health_report_t &packet)
{
if (out_state.chan != chan) {
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "ADSB: Found transceiver on channel %d", chan);
}
out_state.chan_last_ms = AP_HAL::millis();
out_state.chan = chan;
out_state.status = (UAVIONIX_ADSB_RF_HEALTH)packet.rfHealth;
}
void AP_ADSB::send_adsb_out_status(const mavlink_channel_t chan) const
{
for (uint8_t i=0; i < ADSB_MAX_INSTANCES; i++) {
if (_type[i] == (int8_t)(AP_ADSB::Type::uAvionix_UCP) || _type[i] == (int8_t)(AP_ADSB::Type::Sagetech_MXS)) {
mavlink_msg_uavionix_adsb_out_status_send_struct(chan, &out_state.tx_status);
return;
}
}
}
uint32_t AP_ADSB::genICAO(const Location &loc) const
{
const AP_ADSB::Loc &gps { _my_loc };
const uint64_t gps_time = gps.time_epoch_usec();
uint32_t timeSum = 0;
const uint32_t M3 = 4096 * (loc.lat & 0x00000FFF) + (loc.lng & 0x00000FFF);
for (uint8_t i=0; i<24; i++) {
timeSum += (((gps_time & 0x00FFFFFF)>> i) & 0x00000001);
}
return( (timeSum ^ M3) & 0x00FFFFFF);
}
void AP_ADSB::set_callsign(const char* str, const bool append_icao)
{
bool zero_char_pad = false;
memset(out_state.cfg.callsign, 0, sizeof(out_state.cfg.callsign));
for (uint8_t i=0; i<sizeof(out_state.cfg.callsign)-1; i++) {
if (!str[i] || zero_char_pad) {
if ((append_icao && i<4) || zero_char_pad) {
out_state.cfg.callsign[i] = '0';
zero_char_pad = true;
} else {
break;
}
} else if (('A' <= str[i] && str[i] <= 'Z') ||
('0' <= str[i] && str[i] <= '9')) {
out_state.cfg.callsign[i] = str[i];
} else if ('a' <= str[i] && str[i] <= 'z') {
out_state.cfg.callsign[i] = str[i] - ('a' - 'A');
} else if (i == 0) {
out_state.cfg.callsign[i] = '0';
} else {
out_state.cfg.callsign[i] = ' ';
}
}
if (append_icao) {
hal.util->snprintf(&out_state.cfg.callsign[4], 5, "%04X", unsigned(out_state.cfg.ICAO_id % 0x10000));
}
}
void AP_ADSB::push_sample(const adsb_vehicle_t &vehicle)
{
_samples.push(vehicle);
}
bool AP_ADSB::next_sample(adsb_vehicle_t &vehicle)
{
return _samples.pop(vehicle);
}
void AP_ADSB::handle_message(const mavlink_channel_t chan, const mavlink_message_t &msg)
{
switch (msg.msgid) {
case MAVLINK_MSG_ID_ADSB_VEHICLE: {
adsb_vehicle_t vehicle {};
mavlink_msg_adsb_vehicle_decode(&msg, &vehicle.info);
vehicle.last_update_ms = AP_HAL::millis() - uint32_t(vehicle.info.tslc * 1000U);
handle_adsb_vehicle(vehicle);
break;
}
case MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT: {
mavlink_uavionix_adsb_transceiver_health_report_t packet {};
mavlink_msg_uavionix_adsb_transceiver_health_report_decode(&msg, &packet);
handle_transceiver_report(chan, packet);
break;
}
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG: {
mavlink_uavionix_adsb_out_cfg_t packet {};
mavlink_msg_uavionix_adsb_out_cfg_decode(&msg, &packet);
handle_out_cfg(packet);
break;
}
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC:
break;
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL: {
mavlink_uavionix_adsb_out_control_t packet {};
mavlink_msg_uavionix_adsb_out_control_decode(&msg, &packet);
handle_out_control(packet);
break;
}
}
}
bool AP_ADSB::get_vehicle_by_ICAO(const uint32_t icao, adsb_vehicle_t &vehicle) const
{
adsb_vehicle_t temp_vehicle;
temp_vehicle.info.ICAO_address = icao;
uint16_t i;
if (find_index(temp_vehicle, &i)) {
memcpy(&vehicle, &in_state.vehicle_list[i], sizeof(adsb_vehicle_t));
return true;
}
return false;
}
#if HAL_LOGGING_ENABLED
void AP_ADSB::write_log(const adsb_vehicle_t &vehicle) const
{
switch ((Logging)_log) {
case Logging::SPECIAL_ONLY:
if (!is_special_vehicle(vehicle.info.ICAO_address)) {
return;
}
break;
case Logging::ALL:
break;
case Logging::NONE:
default:
return;
}
struct log_ADSB pkt = {
LOG_PACKET_HEADER_INIT(LOG_ADSB_MSG),
time_us : AP_HAL::micros64(),
ICAO_address : vehicle.info.ICAO_address,
lat : vehicle.info.lat,
lng : vehicle.info.lon,
alt : vehicle.info.altitude,
heading : vehicle.info.heading,
hor_velocity : vehicle.info.hor_velocity,
ver_velocity : vehicle.info.ver_velocity,
squawk : vehicle.info.squawk,
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}
#endif
uint32_t AP_ADSB::convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber)
{
if (baseIn != 8 && baseIn != 16) {
return inputNumber;
}
uint32_t outputNumber = 0;
for (uint8_t i=0; i < 10; i++) {
outputNumber += (inputNumber % 10) * powf(baseIn, i);
inputNumber /= 10;
if (inputNumber == 0) break;
}
return outputNumber;
}
bool AP_ADSB::ident_start()
{
if (!healthy()) {
return false;
}
out_state.ctrl.identActive = true;
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"ADSB: IDENT!");
return true;
}
bool AP_ADSB::Loc::speed_accuracy(float &sacc) const
{
if (!horizontal_vel_accuracy_is_valid) {
return false;
}
sacc = horizontal_vel_accuracy;
return true;
}
bool AP_ADSB::Loc::horizontal_accuracy(float &hacc) const
{
if (!horizontal_pos_accuracy_is_valid) {
return false;
}
hacc = horizontal_pos_accuracy;
return true;
}
bool AP_ADSB::Loc::vertical_accuracy(float &vacc) const
{
if (!vertical_pos_accuracy_is_valid) {
return false;
}
vacc = vertical_pos_accuracy;
return true;
}
uint8_t AP_ADSB::convert_maxknots_to_enum(const float maxAircraftSpeed_knots)
{
if (maxAircraftSpeed_knots <= 0) {
return 0;
} else if (maxAircraftSpeed_knots <= 75) {
return 1;
} else if (maxAircraftSpeed_knots <= 150) {
return 2;
} else if (maxAircraftSpeed_knots <= 300) {
return 3;
} else if (maxAircraftSpeed_knots <= 600) {
return 4;
} else if (maxAircraftSpeed_knots <= 1200) {
return 5;
} else {
return 6;
}
}
AP_ADSB *AP::ADSB()
{
return AP_ADSB::get_singleton();
}
#endif