123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492 |
- #include "AP_OADatabase.h"
- #if !HAL_MINIMIZE_FEATURES
- #include <AP_AHRS/AP_AHRS.h>
- #include <GCS_MAVLink/GCS.h>
- #include <AP_Math/AP_Math.h>
- extern const AP_HAL::HAL& hal;
- #ifndef AP_OADATABASE_TIMEOUT_SECONDS_DEFAULT
- #define AP_OADATABASE_TIMEOUT_SECONDS_DEFAULT 10
- #endif
- #ifndef AP_OADATABASE_SIZE_DEFAULT
- #define AP_OADATABASE_SIZE_DEFAULT 100
- #endif
- #ifndef AP_OADATABASE_QUEUE_SIZE_DEFAULT
- #define AP_OADATABASE_QUEUE_SIZE_DEFAULT 80
- #endif
- const AP_Param::GroupInfo AP_OADatabase::var_info[] = {
-
-
-
-
-
-
- AP_GROUPINFO("SIZE", 1, AP_OADatabase, _database_size_param, AP_OADATABASE_SIZE_DEFAULT),
-
-
-
-
-
-
-
- AP_GROUPINFO("EXPIRE", 2, AP_OADatabase, _database_expiry_seconds, AP_OADATABASE_TIMEOUT_SECONDS_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("QUEUE_SIZE", 3, AP_OADatabase, _queue_size_param, AP_OADATABASE_QUEUE_SIZE_DEFAULT),
-
-
-
-
-
- AP_GROUPINFO("OUTPUT", 4, AP_OADatabase, _output_level, (float)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_HIGH),
- AP_GROUPEND
- };
- AP_OADatabase::AP_OADatabase()
- {
- if (_singleton != nullptr) {
- AP_HAL::panic("AP_OADatabase must be singleton");
- }
- _singleton = this;
- AP_Param::setup_object_defaults(this, var_info);
- }
- void AP_OADatabase::init()
- {
- init_database();
- init_queue();
- if (!healthy()) {
- gcs().send_text(MAV_SEVERITY_INFO, "DB init failed . Sizes queue:%u, db:%u", (unsigned int)_queue.size, (unsigned int)_database.size);
- delete _queue.items;
- delete[] _database.items;
- return;
- }
- }
- void AP_OADatabase::update()
- {
- if (!healthy()) {
- return;
- }
- process_queue();
- optimize_db_filter();
- database_items_remove_all_expired();
- }
- void AP_OADatabase::queue_push(const Location &loc, const uint32_t timestamp_ms, const float distance, const float angle)
- {
- if (!healthy()) {
- return;
- }
- AP_OADatabase::OA_DbItemImportance importance = AP_OADatabase::OA_DbItemImportance::Normal;
- if (distance <= 0 || angle < 0 || angle > 360) {
-
- importance = AP_OADatabase::OA_DbItemImportance::Normal;
- } else if (distance < 10 && (angle > (360-10) || angle < 10)) {
-
- importance = AP_OADatabase::OA_DbItemImportance::High;
- } else if (distance < 5 && (angle > (360-30) || angle < 30)) {
-
- importance = AP_OADatabase::OA_DbItemImportance::High;
- } else if (distance < 3 && (angle > (360-90) || angle < 90)) {
-
- importance = AP_OADatabase::OA_DbItemImportance::High;
- } else if (distance < 1.5) {
-
- importance = AP_OADatabase::OA_DbItemImportance::High;
- } else if (distance >= 10) {
-
- importance = AP_OADatabase::OA_DbItemImportance::Low;
- } else if (distance < 5 && (angle <= (360-90) || angle >= 90)) {
-
- importance = AP_OADatabase::OA_DbItemImportance::Low;
- }
- const OA_DbItem item = {loc, timestamp_ms, 0, 0, importance};
- {
- WITH_SEMAPHORE(_queue.sem);
- _queue.items->push(item);
- }
- }
- void AP_OADatabase::init_queue()
- {
- _queue.size = _queue_size_param;
- if (_queue.size == 0) {
- return;
- }
- _queue.items = new ObjectBuffer<OA_DbItem>(_queue.size);
- }
- void AP_OADatabase::init_database()
- {
- _database.size = _database_size_param;
- if (_database_size_param == 0) {
- return;
- }
- _database.items = new OA_DbItem[_database.size];
- }
- void AP_OADatabase::optimize_db_filter()
- {
-
-
-
-
- const float filter_m_backup = _database.filter_m;
- if (_database.count > (_database.size * 0.90f)) {
-
-
- _database.filter_m = MIN(_database.filter_m*_database.filter_grow_rate, _database.filter_max_m);
- } else if (_database.count < (_database.size * 0.85f)) {
-
- _database.filter_m = MAX(_database.filter_m*_database.filter_shrink_rate,_database.filter_min_m);
- }
-
- if (!is_equal(filter_m_backup,_database.filter_m)) {
- _radius_importance_low = MIN(_database.filter_m*4,_database.filter_max_m);
- _radius_importance_normal = _database.filter_m;
- _radius_importance_high = MAX(_database.filter_m*0.25,_database.filter_min_m);
- }
- }
- uint8_t AP_OADatabase::get_send_to_gcs_flags(const OA_DbItemImportance importance)
- {
- switch (importance) {
- case OA_DbItemImportance::Low:
- if (_output_level.get() >= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_ALL) {
- return 0xFF;
- }
- break;
- case OA_DbItemImportance::Normal:
- if (_output_level.get() >= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_HIGH_AND_NORMAL) {
- return 0xFF;
- }
- break;
- case OA_DbItemImportance::High:
- if (_output_level.get() >= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_HIGH) {
- return 0xFF;
- }
- break;
- }
- return 0x0;
- }
- float AP_OADatabase::get_radius(const OA_DbItemImportance importance)
- {
- switch (importance) {
- case OA_DbItemImportance::Low:
- return _radius_importance_low;
- default:
- case OA_DbItemImportance::Normal:
- return _radius_importance_normal;
- case OA_DbItemImportance::High:
- return _radius_importance_high;
- }
- }
- bool AP_OADatabase::process_queue()
- {
- if (!healthy()) {
- return false;
- }
-
-
-
-
-
- const uint16_t queue_available = MIN(_queue.items->available(), 100U);
- if (queue_available == 0) {
- return false;
- }
- for (uint16_t queue_index=0; queue_index<queue_available; queue_index++) {
- OA_DbItem item;
- bool pop_success;
- {
- WITH_SEMAPHORE(_queue.sem);
- pop_success = _queue.items->pop(item);
- }
- if (!pop_success) {
- return false;
- }
- item.radius = get_radius(item.importance);
- item.send_to_gcs = get_send_to_gcs_flags(item.importance);
-
- bool found = false;
- for (uint16_t i=0; i<_database.count; i++) {
- if (is_close_to_item_in_database(i, item)) {
- database_item_refresh(i, item.timestamp_ms, item.radius);
- found = true;
- break;
- }
- }
- if (!found) {
- database_item_add(item);
- }
- }
- return (_queue.items->available() > 0);
- }
- void AP_OADatabase::database_item_add(const OA_DbItem &item)
- {
- if (_database.count >= _database.size) {
- return;
- }
- _database.items[_database.count] = item;
- _database.items[_database.count].send_to_gcs = get_send_to_gcs_flags(_database.items[_database.count].importance);
- _database.count++;
- }
- void AP_OADatabase::database_item_remove(const uint16_t index)
- {
- if (index >= _database.count || _database.count == 0) {
-
- return;
- }
-
- _database.items[index].radius = 0;
- _database.items[index].send_to_gcs = get_send_to_gcs_flags(_database.items[index].importance);
- _database.count--;
- if (_database.count == 0) {
- return;
- }
- if (index != _database.count) {
-
- _database.items[index] = _database.items[_database.count];
- _database.items[index].send_to_gcs = get_send_to_gcs_flags(_database.items[index].importance);
- }
- }
- void AP_OADatabase::database_item_refresh(const uint16_t index, const uint32_t timestamp_ms, const float radius)
- {
- if (index >= _database.count) {
-
- return;
- }
- const bool is_different =
- (!is_equal(_database.items[index].radius, radius)) ||
- (timestamp_ms - _database.items[index].timestamp_ms >= 500);
- if (is_different) {
-
-
- _database.items[index].timestamp_ms = timestamp_ms;
- _database.items[index].radius = radius;
- _database.items[index].send_to_gcs = get_send_to_gcs_flags(_database.items[index].importance);
- }
- }
- void AP_OADatabase::database_items_remove_all_expired()
- {
-
- if (_database_expiry_seconds <= 0) {
-
-
- return;
- }
- const uint32_t now_ms = AP_HAL::millis();
- const uint32_t expiry_ms = (uint32_t)_database_expiry_seconds * 1000;
- uint16_t index = 0;
- while (index < _database.count) {
- if (now_ms - _database.items[index].timestamp_ms > expiry_ms) {
- database_item_remove(index);
- } else {
-
- _database.items[index].radius *= _database.radius_grow_rate;
- if (_database.items[index].radius >= _database.filter_max_m) {
- database_item_remove(index);
- } else {
- index++;
- }
- }
- }
- }
- bool AP_OADatabase::is_close_to_item_in_database(const uint16_t index, const OA_DbItem &item) const
- {
- if (index >= _database.count) {
-
- return false;
- }
- return (_database.items[index].loc.get_distance(item.loc) < item.radius);
- }
- void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms)
- {
-
- static_assert(MAVLINK_COMM_NUM_BUFFERS <= sizeof(OA_DbItem::send_to_gcs) * 8,
- "AP_OADatabase's OA_DBItem.send_to_gcs bitmask must be large enough to hold MAVLINK_COMM_NUM_BUFFERS");
- if ((_output_level.get() <= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_DISABLED) || !healthy()) {
- return;
- }
- const uint8_t chan_as_bitmask = 1 << chan;
- const char callsign[9] = "OA_DB";
-
- const uint32_t now_ms = AP_HAL::millis();
- uint16_t num_to_send = 1;
- uint16_t num_sent = 0;
- if ((_last_send_to_gcs_ms[chan] != 0) && (interval_ms > 0)) {
- uint32_t diff_ms = now_ms - _last_send_to_gcs_ms[chan];
- num_to_send = MAX(diff_ms / interval_ms, 1U);
- }
- _last_send_to_gcs_ms[chan] = now_ms;
-
- for (uint16_t i=0; i < _database.count; i++) {
- if (!HAVE_PAYLOAD_SPACE(chan, ADSB_VEHICLE) || (num_sent >= num_to_send)) {
-
- return;
- }
- const uint16_t idx = _next_index_to_send[chan];
-
- _next_index_to_send[chan]++;
- if (_next_index_to_send[chan] >= _database.count) {
- _next_index_to_send[chan] = 0;
- }
- if ((_database.items[idx].send_to_gcs & chan_as_bitmask) == 0) {
- continue;
- }
- mavlink_msg_adsb_vehicle_send(chan,
- idx,
- _database.items[idx].loc.lat,
- _database.items[idx].loc.lng,
- 0,
- _database.items[idx].loc.alt,
- 0,
- 0,
- 0,
- callsign,
- 255,
- 0,
- 0,
- (uint16_t)(_database.items[idx].radius * 100.f));
-
- _database.items[idx].send_to_gcs &= ~chan_as_bitmask;
-
- _highest_index_sent[chan] = MAX(idx, _highest_index_sent[chan]);
-
- num_sent++;
- }
-
- while (_highest_index_sent[chan] > _database.count) {
- if (!HAVE_PAYLOAD_SPACE(chan, ADSB_VEHICLE) || (num_sent >= num_to_send)) {
-
- return;
- }
- const uint16_t idx = _highest_index_sent[chan];
- _highest_index_sent[chan]--;
- if (_database.items[idx].importance != OA_DbItemImportance::High) {
- continue;
- }
- mavlink_msg_adsb_vehicle_send(chan,
- idx,
- 0,
- 0,
- 0,
- 0,
- 0,
- 0,
- 0,
- callsign,
- 255,
- 0,
- 0,
- 0);
-
- num_sent++;
- }
- }
- AP_OADatabase *AP_OADatabase::_singleton;
- #endif
- namespace AP {
- AP_OADatabase *oadatabase()
- {
- return AP_OADatabase::get_singleton();
- }
- }
|