From 2223216ca262fa5f034cb0555a48322fc53ce9e6 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 10 Jul 2016 16:51:37 -0700 Subject: [PATCH] AP_ADSB: add param ADSB_LIST_RADIUS to ignore distant aircraft --- libraries/AP_ADSB/AP_ADSB.cpp | 15 ++++++++++++++- libraries/AP_ADSB/AP_ADSB.h | 10 ++++++++++ 2 files changed, 24 insertions(+), 1 deletion(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index e53ac623f4..39ebe1bb42 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -51,6 +51,13 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = { AP_GROUPINFO("LIST_MAX", 2, AP_ADSB, in_state.list_size_param, ADSB_VEHICLE_LIST_SIZE_DEFAULT), + // @Param: LIST_RADIUS + // @DisplayName: ADSB vehicle list radius filter + // @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. + // @Range: 1 100000 + // @User: Advanced + AP_GROUPINFO("LIST_RADIUS", 3, AP_ADSB, in_state.list_radius, ADSB_LIST_RADIUS_DEFAULT), + AP_GROUPEND }; @@ -262,7 +269,13 @@ void AP_ADSB::update_vehicle(const mavlink_message_t* packet) adsb_vehicle_t vehicle {}; mavlink_msg_adsb_vehicle_decode(packet, &vehicle.info); - if (find_index(vehicle, &index)) { + if (!_my_loc.is_zero() && + _my_loc.get_distance(AP_ADSB::get_location(vehicle)) > in_state.list_radius) { + + // vehicle is out of range. Ignore it. + return; + + } else if (find_index(vehicle, &index)) { // found, update it set_vehicle(index, vehicle); diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index 988a67c8a7..c28d2f784d 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -25,12 +25,21 @@ #include #include #include +#include +#include #define VEHICLE_THREAT_RADIUS_M 1000 #define VEHICLE_TIMEOUT_MS 10000 // if no updates in this time, drop it from the list #define ADSB_VEHICLE_LIST_SIZE_DEFAULT 25 #define ADSB_VEHICLE_LIST_SIZE_MAX 100 + +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) + #define ADSB_LIST_RADIUS_DEFAULT 10000 // in meters +#else // APM_BUILD_TYPE(APM_BUILD_ArduCopter), Rover, Boat + #define ADSB_LIST_RADIUS_DEFAULT 2000 // in meters +#endif + class AP_ADSB { public: @@ -117,6 +126,7 @@ private: uint16_t list_size = 1; // start with tiny list, then change to param-defined size. This ensures it doesn't fail on start adsb_vehicle_t *vehicle_list = nullptr; uint16_t vehicle_count = 0; + AP_Int32 list_radius; // streamrate stuff uint32_t send_start_ms[MAVLINK_COMM_NUM_BUFFERS];