#pragma once
#include "AP_ADSB_config.h"
#if HAL_ADSB_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Common/Location.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_GPS/AP_GPS_FixType.h>
#define ADSB_MAX_INSTANCES 1
#define ADSB_BITBASK_RF_CAPABILITIES_UAT_IN (1 << 0)
#define ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN (1 << 1)
#define ADSB_BITBASK_RF_CAPABILITIES_UAT_OUT (1 << 2)
#define ADSB_BITBASK_RF_CAPABILITIES_1090ES_OUT (1 << 3)
class AP_ADSB_Backend;
class AP_ADSB {
public:
friend class AP_ADSB_Backend;
friend class AP_ADSB_uAvionix_MAVLink;
friend class AP_ADSB_uAvionix_UCP;
friend class AP_ADSB_Sagetech;
friend class AP_ADSB_Sagetech_MXS;
AP_ADSB();
CLASS_NO_COPY(AP_ADSB);
static AP_ADSB *get_singleton(void) {
return _singleton;
}
enum class Type {
None = 0,
uAvionix_MAVLink = 1,
Sagetech = 2,
uAvionix_UCP = 3,
Sagetech_MXS = 4,
};
struct adsb_vehicle_t {
mavlink_adsb_vehicle_t info;
uint32_t last_update_ms;
};
enum class AdsbOption {
Ping200X_Send_GPS = (1<<0),
Squawk_7400_FS_RC = (1<<1),
Squawk_7400_FS_GCS = (1<<2),
SagteTech_MXS_External_Config = (1<<3),
Mode3_Only = (1<<4),
};
static const struct AP_Param::GroupInfo var_info[];
void update(void);
enum class AltType {
Barometric = 0,
WGS84 = 1,
};
struct Loc : Location {
AltType loc_alt_type;
AP_GPS_FixType fix_type;
uint64_t epoch_us;
uint64_t epoch_from_rtc_us;
bool have_epoch_from_rtc_us;
uint8_t satellites;
float horizontal_pos_accuracy;
bool horizontal_pos_accuracy_is_valid;
float vertical_pos_accuracy;
bool vertical_pos_accuracy_is_valid;
float horizontal_vel_accuracy;
bool horizontal_vel_accuracy_is_valid;
Vector3f vel_ned;
float vertRateD;
bool vertRateD_is_valid;
AP_GPS_FixType status() const { return fix_type; }
const Vector3f &velocity() const {
return vel_ned;
}
uint64_t time_epoch_usec() const { return epoch_us; }
bool speed_accuracy(float &sacc) const;
bool horizontal_accuracy(float &hacc) const;
bool vertical_accuracy(float &vacc) const;
uint8_t num_sats() const { return satellites; }
const Vector2f &groundspeed_vector() const { return vel_ned.xy(); }
bool get_vert_pos_rate_D(float &velocity) const {
velocity = vertRateD;
return vertRateD_is_valid;
}
bool baro_is_healthy;
float baro_alt_press_diff_sea_level;
} _my_loc;
void update(const Loc &loc);
void send_adsb_vehicle(mavlink_channel_t chan);
bool set_stall_speed_cm(const uint16_t stall_speed_cm) {
if (out_state.cfg.was_set_externally) {
return false;
}
out_state.cfg.stall_speed_cm = stall_speed_cm;
return true;
}
bool set_max_speed(int16_t max_speed) {
if (out_state.cfg.was_set_externally) {
return false;
}
out_state.cfg.maxAircraftSpeed_knots = (float)max_speed * M_PER_SEC_TO_KNOTS;
return true;
}
void set_is_auto_mode(const bool is_in_auto_mode) { out_state.is_in_auto_mode = is_in_auto_mode; }
void set_is_flying(const bool is_flying) { out_state.is_flying = is_flying; }
Location get_location(const adsb_vehicle_t &vehicle) const;
bool enabled() const {
for (uint8_t instance=0; instance<detected_num_instances; instance++) {
if (_type[instance] > 0) {
return true;
}
}
return false;
}
bool init_failed() const {
return _init_failed;
}
bool healthy() {
return check_startup();
}
bool next_sample(adsb_vehicle_t &obstacle);
void handle_adsb_vehicle(const adsb_vehicle_t &vehicle);
void handle_message(const mavlink_channel_t chan, const mavlink_message_t &msg);
void send_adsb_out_status(const mavlink_channel_t chan) const;
bool get_vehicle_by_ICAO(const uint32_t icao, adsb_vehicle_t &vehicle) const;
uint32_t get_special_ICAO_target() const { return (uint32_t)_special_ICAO_target; };
void set_special_ICAO_target(const uint32_t new_icao_target) { _special_ICAO_target.set((int32_t)new_icao_target); };
bool is_special_vehicle(uint32_t icao) const { return _special_ICAO_target != 0 && (_special_ICAO_target == (int32_t)icao); }
static bool is_valid_callsign(uint16_t octal) WARN_IF_UNUSED;
static uint8_t convert_maxknots_to_enum(const float maxAircraftSpeed_knots);
static uint32_t convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber);
bool ident_start();
AP_ADSB::Type get_type(uint8_t instance) const;
private:
static AP_ADSB *_singleton;
void init();
bool check_startup();
void determine_furthest_aircraft(void);
bool find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const;
void delete_vehicle(const uint16_t index);
void set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle);
uint32_t genICAO(const Location &loc) const;
void set_callsign(const char* str, const bool append_icao);
void handle_out_cfg(const mavlink_uavionix_adsb_out_cfg_t &packet);
void handle_out_control(const mavlink_uavionix_adsb_out_control_t &packet);
void handle_transceiver_report(const mavlink_channel_t chan, const mavlink_uavionix_adsb_transceiver_health_report_t &packet);
void detect_instance(uint8_t instance);
AP_Int8 _type[ADSB_MAX_INSTANCES];
bool _init_failed;
struct {
AP_Int16 list_size_param;
uint16_t list_size_allocated;
adsb_vehicle_t *vehicle_list;
uint16_t vehicle_count;
AP_Int32 list_radius;
AP_Int16 list_altitude;
uint16_t furthest_vehicle_index;
float furthest_vehicle_distance;
uint32_t send_start_ms[MAVLINK_COMM_NUM_BUFFERS];
uint16_t send_index[MAVLINK_COMM_NUM_BUFFERS];
} in_state;
struct {
uint32_t last_config_ms;
uint32_t last_report_ms;
int8_t chan = -1;
uint32_t chan_last_ms;
UAVIONIX_ADSB_RF_HEALTH status;
bool is_flying;
bool is_in_auto_mode;
struct {
int32_t ICAO_id;
AP_Int32 ICAO_id_param;
int32_t ICAO_id_param_prev = -1;
char callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN];
AP_Int8 emitterType;
AP_Int8 lengthWidth;
AP_Int8 gpsOffsetLat;
AP_Int8 gpsOffsetLon;
uint16_t stall_speed_cm;
AP_Int8 rfSelect;
AP_Int16 squawk_octal_param;
uint16_t squawk_octal;
float maxAircraftSpeed_knots;
AP_Int8 rf_capable;
bool was_set_externally;
} cfg;
struct {
bool baroCrossChecked;
uint8_t airGroundState;
bool identActive;
bool modeAEnabled;
bool modeCEnabled;
bool modeSEnabled;
bool es1090TxEnabled;
int32_t externalBaroAltitude_mm;
uint16_t squawkCode;
uint8_t emergencyState;
uint8_t callsign[8];
bool x_bit;
} ctrl;
mavlink_uavionix_adsb_out_status_t tx_status;
} out_state;
uint8_t detected_num_instances;
AP_Int32 _special_ICAO_target;
AP_Int32 _options;
static const uint8_t _max_samples = 30;
ObjectBuffer<adsb_vehicle_t> _samples{_max_samples};
void push_sample(const adsb_vehicle_t &vehicle);
void write_log(const adsb_vehicle_t &vehicle) const;
enum class Logging {
NONE = 0,
SPECIAL_ONLY = 1,
ALL = 2
};
AP_Enum<Logging> _log;
AP_ADSB_Backend *_backend[ADSB_MAX_INSTANCES];
};
namespace AP {
AP_ADSB *ADSB();
};
#endif