mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ADSB: added handle_adsb_vehicle() API
this allows for UAVCAN ADSB adapters
This commit is contained in:
parent
8650229ad4
commit
df90cee8a0
@ -413,7 +413,7 @@ bool AP_ADSB::find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const
|
|||||||
* Update the vehicle list. If the vehicle is already in the
|
* Update the vehicle list. If the vehicle is already in the
|
||||||
* list then it will update it, otherwise it will be added.
|
* list then it will update it, otherwise it will be added.
|
||||||
*/
|
*/
|
||||||
void AP_ADSB::handle_vehicle(const mavlink_message_t &packet)
|
void AP_ADSB::handle_adsb_vehicle(const adsb_vehicle_t &vehicle)
|
||||||
{
|
{
|
||||||
if (in_state.vehicle_list == nullptr) {
|
if (in_state.vehicle_list == nullptr) {
|
||||||
// We are only null when disabled. Updating is inhibited.
|
// We are only null when disabled. Updating is inhibited.
|
||||||
@ -421,8 +421,6 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t &packet)
|
|||||||
}
|
}
|
||||||
|
|
||||||
uint16_t index = in_state.list_size + 1; // initialize with invalid index
|
uint16_t index = in_state.list_size + 1; // initialize with invalid index
|
||||||
adsb_vehicle_t vehicle {};
|
|
||||||
mavlink_msg_adsb_vehicle_decode(&packet, &vehicle.info);
|
|
||||||
const Location vehicle_loc = AP_ADSB::get_location(vehicle);
|
const Location vehicle_loc = AP_ADSB::get_location(vehicle);
|
||||||
const bool my_loc_is_zero = _my_loc.is_zero();
|
const bool my_loc_is_zero = _my_loc.is_zero();
|
||||||
const float my_loc_distance_to_vehicle = _my_loc.get_distance(vehicle_loc);
|
const float my_loc_distance_to_vehicle = _my_loc.get_distance(vehicle_loc);
|
||||||
@ -432,9 +430,6 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t &packet)
|
|||||||
const bool is_tracked_in_list = find_index(vehicle, &index);
|
const bool is_tracked_in_list = find_index(vehicle, &index);
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
|
|
||||||
// note the last time the receiver got a packet from the aircraft
|
|
||||||
vehicle.last_update_ms = now - (vehicle.info.tslc * 1000);
|
|
||||||
|
|
||||||
const uint16_t required_flags_position = ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE;
|
const uint16_t required_flags_position = ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE;
|
||||||
const bool detected_ourself = (out_state.cfg.ICAO_id != 0) && ((uint32_t)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);
|
||||||
|
|
||||||
@ -500,6 +495,19 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t &packet)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Update the vehicle list. If the vehicle is already in the
|
||||||
|
* list then it will update it, otherwise it will be added.
|
||||||
|
*/
|
||||||
|
void AP_ADSB::handle_vehicle(const mavlink_message_t &packet)
|
||||||
|
{
|
||||||
|
adsb_vehicle_t vehicle {};
|
||||||
|
const uint32_t now = AP_HAL::millis();
|
||||||
|
mavlink_msg_adsb_vehicle_decode(&packet, &vehicle.info);
|
||||||
|
vehicle.last_update_ms = now - (vehicle.info.tslc * 1000);
|
||||||
|
handle_adsb_vehicle(vehicle);
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Copy a vehicle's data into the list
|
* Copy a vehicle's data into the list
|
||||||
*/
|
*/
|
||||||
@ -871,7 +879,7 @@ void AP_ADSB::set_callsign(const char* str, const bool append_icao)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void AP_ADSB::push_sample(adsb_vehicle_t &vehicle)
|
void AP_ADSB::push_sample(const adsb_vehicle_t &vehicle)
|
||||||
{
|
{
|
||||||
samples.push(vehicle);
|
samples.push(vehicle);
|
||||||
}
|
}
|
||||||
|
@ -73,6 +73,9 @@ public:
|
|||||||
}
|
}
|
||||||
bool next_sample(adsb_vehicle_t &obstacle);
|
bool next_sample(adsb_vehicle_t &obstacle);
|
||||||
|
|
||||||
|
// handle a adsb_vehicle_t from an external source (used for UAVCAN)
|
||||||
|
void handle_adsb_vehicle(const adsb_vehicle_t &vehicle);
|
||||||
|
|
||||||
// mavlink message handler
|
// mavlink message handler
|
||||||
void handle_message(const mavlink_channel_t chan, const mavlink_message_t &msg);
|
void handle_message(const mavlink_channel_t chan, const mavlink_message_t &msg);
|
||||||
|
|
||||||
@ -197,7 +200,7 @@ private:
|
|||||||
static const uint8_t max_samples = 30;
|
static const uint8_t max_samples = 30;
|
||||||
ObjectBuffer<adsb_vehicle_t> samples{max_samples};
|
ObjectBuffer<adsb_vehicle_t> samples{max_samples};
|
||||||
|
|
||||||
void push_sample(adsb_vehicle_t &vehicle);
|
void push_sample(const adsb_vehicle_t &vehicle);
|
||||||
|
|
||||||
// logging
|
// logging
|
||||||
AP_Int8 _log;
|
AP_Int8 _log;
|
||||||
|
Loading…
Reference in New Issue
Block a user