AP_ADSB: fixed signed int compare compile warning/error and reject >24bit ICAO

- The value is only 24bits anyway so sign conversion does not matter
- also reject ICAO values > 24bits
This commit is contained in:
Tom Pittenger 2016-08-16 18:49:48 -07:00
parent 78e7acf25c
commit 1612110d16
1 changed files with 2 additions and 1 deletions

View File

@ -346,11 +346,12 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t* packet)
vehicle.last_update_ms = now - (vehicle.info.tslc * 1000);
const uint16_t required_flags_position = ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE;
const bool detected_ourself = (out_state.cfg.ICAO_id != 0) && (out_state.cfg.ICAO_id == vehicle.info.ICAO_address);
const bool detected_ourself = (out_state.cfg.ICAO_id != 0) && ((uint32_t)out_state.cfg.ICAO_id == vehicle.info.ICAO_address);
if (vehicle_loc.is_zero() ||
out_of_range ||
detected_ourself ||
(vehicle.info.ICAO_address > 0x00FFFFFF) || // ICAO address is 24bits, so ignore higher values.
!(vehicle.info.flags & required_flags_position) ||
now - vehicle.last_update_ms > VEHICLE_TIMEOUT_MS) {