31 #define VEHICLE_TIMEOUT_MS 5000 // if no updates in this time, drop it from the list 32 #define ADSB_VEHICLE_LIST_SIZE_DEFAULT 25 33 #define ADSB_VEHICLE_LIST_SIZE_MAX 100 34 #define ADSB_CHAN_TIMEOUT_MS 15000 35 #define ADSB_SQUAWK_OCTAL_DEFAULT 1200 37 #define ADSB_BITBASK_RF_CAPABILITIES_UAT_IN (1 << 0) 38 #define ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN (1 << 1) 40 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) 41 #define ADSB_LIST_RADIUS_DEFAULT 10000 // in meters 42 #else // APM_BUILD_TYPE(APM_BUILD_ArduCopter), Rover, Boat 43 #define ADSB_LIST_RADIUS_DEFAULT 2000 // in meters 93 AP_GROUPINFO(
"LEN_WIDTH", 6,
AP_ADSB, out_state.
cfg.lengthWidth, UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M),
100 AP_GROUPINFO(
"OFFSET_LAT", 7,
AP_ADSB, out_state.
cfg.gpsLatOffset, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M),
107 AP_GROUPINFO(
"OFFSET_LON", 8,
AP_ADSB, out_state.
cfg.gpsLonOffset, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR),
142 if (
in_state.vehicle_list ==
nullptr) {
150 if (
in_state.vehicle_list ==
nullptr) {
152 hal.
console->
printf(
"Unable to initialize ADS-B vehicle list\n");
170 if (
in_state.vehicle_list !=
nullptr) {
187 if (
in_state.vehicle_list !=
nullptr) {
192 }
else if (
in_state.vehicle_list ==
nullptr) {
204 while (index <
in_state.vehicle_count) {
262 gcs().
send_text(MAV_SEVERITY_ERROR,
"ADSB: Transceiver heartbeat timed out");
264 mavlink_channel_t
chan = (mavlink_channel_t)(MAVLINK_COMM_0 +
out_state.chan);
284 float max_distance = 0;
285 uint16_t max_distance_index = 0;
287 for (uint16_t index = 0; index <
in_state.vehicle_count; index++) {
289 if (max_distance < distance || index == 0) {
291 max_distance_index = index;
307 vehicle.
info.altitude * 0.1f,
319 if (index <
in_state.vehicle_count) {
325 if (index != (
in_state.vehicle_count-1)) {
341 for (uint16_t i = 0; i <
in_state.vehicle_count; i++) {
342 if (
in_state.vehicle_list[i].info.ICAO_address == vehicle.
info.ICAO_address) {
356 if (
in_state.vehicle_list ==
nullptr) {
361 uint16_t index =
in_state.list_size + 1;
363 mavlink_msg_adsb_vehicle_decode(packet, &
vehicle.info);
367 bool out_of_range =
in_state.list_radius > 0 && !my_loc_is_zero && my_loc_distance_to_vehicle >
in_state.list_radius;
374 const uint16_t required_flags_position = ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE;
375 const bool detected_ourself = (
out_state.cfg.ICAO_id != 0) && ((uint32_t)
out_state.cfg.ICAO_id ==
vehicle.info.ICAO_address);
380 (
vehicle.info.ICAO_address > 0x00FFFFFF) ||
381 !(
vehicle.info.flags & required_flags_position) ||
385 if (is_tracked_in_list) {
390 }
else if (is_tracked_in_list) {
404 if (my_loc_is_zero) {
427 const uint16_t required_flags_avoidance =
428 ADSB_FLAGS_VALID_COORDS |
429 ADSB_FLAGS_VALID_ALTITUDE |
430 ADSB_FLAGS_VALID_HEADING |
431 ADSB_FLAGS_VALID_VELOCITY;
433 if (
vehicle.info.flags & required_flags_avoidance) {
458 if (now -
in_state.send_start_ms[chan] < 1000) {
472 mavlink_msg_adsb_vehicle_send(chan,
473 vehicle.ICAO_address,
476 vehicle.altitude_type,
479 vehicle.hor_velocity,
480 vehicle.ver_velocity,
482 vehicle.emitter_type,
498 const int16_t velVert = gps_velocity.
z * 1E2;
499 const int16_t nsVog = gps_velocity.
x * 1E2;
500 const int16_t ewVog = gps_velocity.
y * 1E2;
501 const uint8_t fixType = gps.
status();
502 const uint8_t emStatus = 0;
503 const uint8_t numSats = gps.
num_sats();
504 const uint16_t squawk =
out_state.cfg.squawk_octal;
506 uint32_t accHoriz = UINT_MAX;
509 accHoriz = accHoriz_f * 1E3;
512 uint16_t accVert = USHRT_MAX;
515 accVert = accVert_f * 1E2;
518 uint16_t accVel = USHRT_MAX;
521 accVel = accVel_f * 1E3;
526 state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED;
529 state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND;
534 const uint32_t utcTime = gps_time / 1000000ULL;
537 int32_t altPres = INT_MAX;
545 mavlink_msg_uavionix_adsb_out_dynamic_send(
577 uint32_t encoded_icao = (uint32_t)
out_state.cfg.ICAO_id & 0x00FFFFFF;
579 encoded_icao &= ~0x20000000;
580 encoded_icao |= 0x10000000;
583 encoded_icao &= ~0x03000000;
584 encoded_icao &= ~0x0C000000;
606 uint8_t encoded_null = 0;
608 if (
out_state.cfg.maxAircraftSpeed_knots <= 0) {
610 }
else if (
out_state.cfg.maxAircraftSpeed_knots <= 75) {
611 encoded_null |= 0x01;
612 }
else if (
out_state.cfg.maxAircraftSpeed_knots <= 150) {
613 encoded_null |= 0x02;
614 }
else if (
out_state.cfg.maxAircraftSpeed_knots <= 300) {
615 encoded_null |= 0x03;
616 }
else if (
out_state.cfg.maxAircraftSpeed_knots <= 600) {
617 encoded_null |= 0x04;
618 }
else if (
out_state.cfg.maxAircraftSpeed_knots <= 1200) {
619 encoded_null |= 0x05;
621 encoded_null |= 0x06;
626 encoded_null |= 0x10;
629 encoded_null |= 0x20;
643 memset(&
out_state.cfg.callsign[4], 0, 5);
644 encoded_null |= 0x40;
656 mavlink_uavionix_adsb_out_cfg_t packet {};
657 mavlink_msg_uavionix_adsb_out_cfg_decode(msg, &packet);
662 out_state.cfg.ICAO_id_param =
out_state.cfg.ICAO_id_param_prev = packet.ICAO & 0x00FFFFFFFF;
667 out_state.cfg.emitterType = packet.emitterType;
668 out_state.cfg.lengthWidth = packet.aircraftSize;
669 out_state.cfg.gpsLatOffset = packet.gpsOffsetLat;
670 out_state.cfg.gpsLonOffset = packet.gpsOffsetLon;
671 out_state.cfg.rfSelect = packet.rfSelect;
672 out_state.cfg.stall_speed_cm = packet.stallSpeed;
675 char c =
out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1];
676 out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = 0;
678 out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = c;
692 int8_t
callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN];
705 mavlink_msg_uavionix_adsb_out_cfg_send(
708 (
const char*)callsign,
724 mavlink_uavionix_adsb_transceiver_health_report_t packet {};
725 mavlink_msg_uavionix_adsb_transceiver_health_report_decode(msg, &packet);
728 gcs().
send_text(MAV_SEVERITY_DEBUG,
"ADSB: Found transceiver on channel %d", chan);
733 out_state.status = (UAVIONIX_ADSB_RF_HEALTH)packet.rfHealth;
749 uint32_t timeSum = 0;
750 uint32_t M3 = 4096 * (loc.
lat & 0x00000FFF) + (loc.
lng & 0x00000FFF);
752 for (uint8_t i=0; i<24; i++) {
753 timeSum += (((gps_time & 0x00FFFFFF)>> i) & 0x00000001);
755 return( (timeSum ^ M3) & 0x00FFFFFF);
761 bool zero_char_pad =
false;
768 for (uint8_t i=0; i<
sizeof(
out_state.cfg.callsign)-1; i++) {
769 if (!str[i] || zero_char_pad) {
771 if ((append_icao && i<4) || zero_char_pad) {
773 zero_char_pad =
true;
779 }
else if ((
'A' <= str[i] && str[i] <=
'Z') ||
780 (
'0' <= str[i] && str[i] <=
'9')) {
785 }
else if (
'a' <= str[i] && str[i] <=
'z') {
787 out_state.cfg.callsign[i] = str[i] - (
'a' -
'A');
812 return samples.pop_front(vehicle);
817 switch (msg->msgid) {
818 case MAVLINK_MSG_ID_ADSB_VEHICLE:
821 case MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT:
825 case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG:
829 case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC:
struct AP_ADSB::@1 in_state
void send_adsb_vehicle(mavlink_channel_t chan)
void determine_furthest_aircraft(void)
bool next_sample(adsb_vehicle_t &obstacle)
#define AP_PARAM_FLAG_ENABLE
void set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle)
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
uint32_t get_encoded_icao(void)
AP_HAL::UARTDriver * console
uint8_t get_encoded_callsign_null_char(void)
Interface definition for the various Ground Control System.
#define ADSB_VEHICLE_LIST_SIZE_MAX
#define AP_GROUPINFO(name, idx, clazz, element, def)
void push_sample(adsb_vehicle_t &vehicle)
bool is_valid_octal(uint16_t octal)
uint32_t genICAO(const Location_Class &loc)
#define ADSB_SQUAWK_OCTAL_DEFAULT
static void gps_time(uint16_t *time_week, uint32_t *time_week_ms)
void handle_vehicle(const mavlink_message_t *msg)
#define ADSB_BITBASK_RF_CAPABILITIES_UAT_IN
void handle_transceiver_report(mavlink_channel_t chan, const mavlink_message_t *msg)
int32_t lat
param 3 - Latitude * 10**7
float get_altitude_difference(float base_pressure, float pressure) const
bool find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const
char callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN]
static const struct AP_Param::GroupInfo var_info[]
void handle_out_cfg(const mavlink_message_t *msg)
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
void set_callsign(const char *str, const bool append_icao)
#define HAVE_PAYLOAD_SPACE(chan, id)
virtual void printf(const char *,...) FMT_PRINTF(2
const Vector3f & velocity(uint8_t instance) const
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
AP_Buffer< adsb_vehicle_t, max_samples > samples
bool speed_accuracy(uint8_t instance, float &sacc) const
#define VEHICLE_TIMEOUT_MS
void handle_message(const mavlink_channel_t chan, const mavlink_message_t *msg)
mavlink_adsb_vehicle_t info
struct AP_ADSB::@2::@3 cfg
void send_dynamic_out(const mavlink_channel_t chan)
Location_Class get_location(const adsb_vehicle_t &vehicle) const
static DummyVehicle vehicle
struct AP_ADSB::@2 out_state
void send_text(MAV_SEVERITY severity, const char *fmt,...)
float get_pressure(void) const
GPS_Status status(uint8_t instance) const
Query GPS status.
uint16_t furthest_vehicle_index
int32_t lng
param 4 - Longitude * 10**7
uint8_t num_sats(uint8_t instance) const
float get_distance(const struct Location &loc2) const
#define ADSB_CHAN_TIMEOUT_MS
#define ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN
int snprintf(char *str, size_t size, const char *fmt,...)
uint64_t time_epoch_usec(uint8_t instance) const
void send_configure(const mavlink_channel_t chan)
#define ADSB_VEHICLE_LIST_SIZE_DEFAULT
float furthest_vehicle_distance
bool vertical_accuracy(uint8_t instance, float &vacc) const
bool horizontal_accuracy(uint8_t instance, float &hacc) const
#define ADSB_LIST_RADIUS_DEFAULT
void delete_vehicle(const uint16_t index)
#define MAVLINK_COMM_NUM_BUFFERS