mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
ADSB: add param ADSB_LIST_ALT to filter aircraft by altitude. default is disabled
This commit is contained in:
parent
587e02e92e
commit
6145711931
@ -66,9 +66,10 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = {
|
|||||||
|
|
||||||
// @Param: LIST_RADIUS
|
// @Param: LIST_RADIUS
|
||||||
// @DisplayName: ADSB vehicle list radius filter
|
// @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.
|
// @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. A value of 0 will disable this filter.
|
||||||
// @Range: 1 100000
|
// @Range: 0 100000
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
|
// @Units: m
|
||||||
AP_GROUPINFO("LIST_RADIUS", 3, AP_ADSB, in_state.list_radius, ADSB_LIST_RADIUS_DEFAULT),
|
AP_GROUPINFO("LIST_RADIUS", 3, AP_ADSB, in_state.list_radius, ADSB_LIST_RADIUS_DEFAULT),
|
||||||
|
|
||||||
// @Param: ICAO_ID
|
// @Param: ICAO_ID
|
||||||
@ -129,6 +130,14 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("RF_CAPABLE", 11, AP_ADSB, out_state.cfg.rf_capable, 0),
|
AP_GROUPINFO("RF_CAPABLE", 11, AP_ADSB, out_state.cfg.rf_capable, 0),
|
||||||
|
|
||||||
|
// @Param: LIST_ALT
|
||||||
|
// @DisplayName: ADSB vehicle list altitude filter
|
||||||
|
// @Description: ADSB vehicle list altitude filter. Vehicles detected above this altitude 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. A value of 0 will disable this filter.
|
||||||
|
// @Range: 0 32767
|
||||||
|
// @User: Advanced
|
||||||
|
// @Units: m
|
||||||
|
AP_GROUPINFO("LIST_ALT", 12, AP_ADSB, in_state.list_altitude, 0),
|
||||||
|
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
@ -366,6 +375,7 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t* packet)
|
|||||||
bool my_loc_is_zero = _my_loc.is_zero();
|
bool my_loc_is_zero = _my_loc.is_zero();
|
||||||
float my_loc_distance_to_vehicle = _my_loc.get_distance(vehicle_loc);
|
float my_loc_distance_to_vehicle = _my_loc.get_distance(vehicle_loc);
|
||||||
bool out_of_range = in_state.list_radius > 0 && !my_loc_is_zero && my_loc_distance_to_vehicle > in_state.list_radius;
|
bool out_of_range = in_state.list_radius > 0 && !my_loc_is_zero && my_loc_distance_to_vehicle > in_state.list_radius;
|
||||||
|
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;
|
||||||
bool is_tracked_in_list = find_index(vehicle, &index);
|
bool is_tracked_in_list = find_index(vehicle, &index);
|
||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
|
|
||||||
@ -377,6 +387,7 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t* packet)
|
|||||||
|
|
||||||
if (vehicle_loc.is_zero() ||
|
if (vehicle_loc.is_zero() ||
|
||||||
out_of_range ||
|
out_of_range ||
|
||||||
|
out_of_range_alt ||
|
||||||
detected_ourself ||
|
detected_ourself ||
|
||||||
(vehicle.info.ICAO_address > 0x00FFFFFF) || // ICAO address is 24bits, so ignore higher values.
|
(vehicle.info.ICAO_address > 0x00FFFFFF) || // ICAO address is 24bits, so ignore higher values.
|
||||||
!(vehicle.info.flags & required_flags_position) ||
|
!(vehicle.info.flags & required_flags_position) ||
|
||||||
|
@ -133,6 +133,7 @@ private:
|
|||||||
adsb_vehicle_t *vehicle_list = nullptr;
|
adsb_vehicle_t *vehicle_list = nullptr;
|
||||||
uint16_t vehicle_count;
|
uint16_t vehicle_count;
|
||||||
AP_Int32 list_radius;
|
AP_Int32 list_radius;
|
||||||
|
AP_Int16 list_altitude;
|
||||||
|
|
||||||
// streamrate stuff
|
// streamrate stuff
|
||||||
uint32_t send_start_ms[MAVLINK_COMM_NUM_BUFFERS];
|
uint32_t send_start_ms[MAVLINK_COMM_NUM_BUFFERS];
|
||||||
|
Loading…
Reference in New Issue
Block a user