mirror of https://github.com/ArduPilot/ardupilot
AP_ADSB: adjust for Location_Class and Location unification
This commit is contained in:
parent
0215aff8f4
commit
384ab476b4
|
@ -300,13 +300,13 @@ void AP_ADSB::determine_furthest_aircraft(void)
|
|||
/*
|
||||
* Convert/Extract a Location from a vehicle
|
||||
*/
|
||||
Location_Class AP_ADSB::get_location(const adsb_vehicle_t &vehicle) const
|
||||
Location AP_ADSB::get_location(const adsb_vehicle_t &vehicle) const
|
||||
{
|
||||
Location_Class loc = Location_Class(
|
||||
Location loc = Location(
|
||||
vehicle.info.lat,
|
||||
vehicle.info.lon,
|
||||
vehicle.info.altitude * 0.1f,
|
||||
Location_Class::ALT_FRAME_ABSOLUTE);
|
||||
Location::ALT_FRAME_ABSOLUTE);
|
||||
|
||||
return loc;
|
||||
}
|
||||
|
@ -362,7 +362,7 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t* packet)
|
|||
uint16_t index = in_state.list_size + 1; // initialize with invalid index
|
||||
adsb_vehicle_t vehicle {};
|
||||
mavlink_msg_adsb_vehicle_decode(packet, &vehicle.info);
|
||||
Location_Class vehicle_loc = Location_Class(AP_ADSB::get_location(vehicle));
|
||||
const Location vehicle_loc = AP_ADSB::get_location(vehicle);
|
||||
bool my_loc_is_zero = _my_loc.is_zero();
|
||||
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;
|
||||
|
@ -740,7 +740,7 @@ void AP_ADSB::handle_transceiver_report(const mavlink_channel_t chan, const mavl
|
|||
|
||||
Note gps.time is the number of seconds since UTC midnight
|
||||
*/
|
||||
uint32_t AP_ADSB::genICAO(const Location_Class &loc)
|
||||
uint32_t AP_ADSB::genICAO(const Location &loc)
|
||||
{
|
||||
// gps_time is not seconds since UTC midnight, but it is an equivalent random number
|
||||
// TODO: use UTC time instead of GPS time
|
||||
|
|
|
@ -70,7 +70,7 @@ public:
|
|||
UAVIONIX_ADSB_RF_HEALTH get_transceiver_status(void) { return out_state.status; }
|
||||
|
||||
// extract a location out of a vehicle item
|
||||
Location_Class get_location(const adsb_vehicle_t &vehicle) const;
|
||||
Location get_location(const adsb_vehicle_t &vehicle) const;
|
||||
|
||||
bool enabled() const {
|
||||
return _enabled;
|
||||
|
@ -99,7 +99,7 @@ private:
|
|||
void set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle);
|
||||
|
||||
// Generates pseudorandom ICAO from gps time, lat, and lon
|
||||
uint32_t genICAO(const Location_Class &loc);
|
||||
uint32_t genICAO(const Location &loc);
|
||||
|
||||
// set callsign: 8char string (plus null termination) then optionally append last 4 digits of icao
|
||||
void set_callsign(const char* str, const bool append_icao);
|
||||
|
@ -122,7 +122,7 @@ private:
|
|||
|
||||
AP_Int8 _enabled;
|
||||
|
||||
Location_Class _my_loc;
|
||||
Location _my_loc;
|
||||
|
||||
|
||||
// ADSB-IN state. Maintains list of external vehicles
|
||||
|
|
Loading…
Reference in New Issue