AP_ADSB: add param ADSB_LIST_RADIUS to ignore distant aircraft

This commit is contained in:
Tom Pittenger 2016-07-10 16:51:37 -07:00
parent 454560ca4c
commit 2223216ca2
2 changed files with 24 additions and 1 deletions

View File

@ -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);

View File

@ -25,12 +25,21 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_Common/Location.h>
#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];