Path: blob/master/libraries/AC_Avoidance/AP_OADatabase.cpp
4182 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.5This program is distributed in the hope that it will be useful,6but WITHOUT ANY WARRANTY; without even the implied warranty of7MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the8GNU General Public License for more details.9You should have received a copy of the GNU General Public License10along with this program. If not, see <http://www.gnu.org/licenses/>.11*/1213#include "AC_Avoidance_config.h"1415#if AP_OADATABASE_ENABLED1617#include "AP_OADatabase.h"1819#include <AP_AHRS/AP_AHRS.h>20#include <GCS_MAVLink/GCS.h>21#include <AP_Math/AP_Math.h>22#include <AP_Vehicle/AP_Vehicle_Type.h>2324extern const AP_HAL::HAL& hal;2526#ifndef AP_OADATABASE_TIMEOUT_SECONDS_DEFAULT27#define AP_OADATABASE_TIMEOUT_SECONDS_DEFAULT 1028#endif2930#ifndef AP_OADATABASE_SIZE_DEFAULT31#define AP_OADATABASE_SIZE_DEFAULT 10032#endif3334#ifndef AP_OADATABASE_QUEUE_SIZE_DEFAULT35#define AP_OADATABASE_QUEUE_SIZE_DEFAULT 8036#endif3738#ifndef AP_OADATABASE_DISTANCE_FROM_HOME39#define AP_OADATABASE_DISTANCE_FROM_HOME 340#endif4142const AP_Param::GroupInfo AP_OADatabase::var_info[] = {4344// @Param: SIZE45// @DisplayName: OADatabase maximum number of points46// @Description: OADatabase maximum number of points. Set to 0 to disable the OA Database. Larger means more points but is more cpu intensive to process47// @Range: 0 1000048// @User: Advanced49// @RebootRequired: True50AP_GROUPINFO("SIZE", 1, AP_OADatabase, _database_size_param, AP_OADATABASE_SIZE_DEFAULT),5152// @Param: EXPIRE53// @DisplayName: OADatabase item timeout54// @Description: OADatabase item timeout. The time an item will linger without any updates before it expires. Zero means never expires which is useful for a sent-once static environment but terrible for dynamic ones.55// @Units: s56// @Range: 0 50057// @Increment: 158// @User: Advanced59AP_GROUPINFO("EXPIRE", 2, AP_OADatabase, _database_expiry_seconds, AP_OADATABASE_TIMEOUT_SECONDS_DEFAULT),6061// @Param: QUEUE_SIZE62// @DisplayName: OADatabase queue maximum number of points63// @Description: OADatabase queue maximum number of points. This in an input buffer size. Larger means it can handle larger bursts of incoming data points to filter into the database. No impact on cpu, only RAM. Recommend larger for faster datalinks or for sensors that generate a lot of data.64// @Range: 1 20065// @User: Advanced66// @RebootRequired: True67AP_GROUPINFO("QUEUE_SIZE", 3, AP_OADatabase, _queue_size_param, AP_OADATABASE_QUEUE_SIZE_DEFAULT),6869// @Param: OUTPUT70// @DisplayName: OADatabase output level71// @Description: OADatabase output level to configure which database objects are sent to the ground station. All data is always available internally for avoidance algorithms.72// @Values: 0:Disabled,1:Send only HIGH importance items,2:Send HIGH and NORMAL importance items,3:Send all items73// @User: Advanced74AP_GROUPINFO("OUTPUT", 4, AP_OADatabase, _output_level, (float)OutputLevel::HIGH),7576// @Param: BEAM_WIDTH77// @DisplayName: OADatabase beam width78// @Description: Beam width of incoming lidar data, used to calculate a object radius if none is provided by the data source.79// @Units: deg80// @Range: 1 1081// @User: Advanced82// @RebootRequired: True83AP_GROUPINFO("BEAM_WIDTH", 5, AP_OADatabase, _beam_width, 5.0f),8485// @Param: RADIUS_MIN86// @DisplayName: OADatabase Minimum radius87// @Description: Minimum radius of objects held in database88// @Units: m89// @Range: 0 1090// @User: Advanced91AP_GROUPINFO("RADIUS_MIN", 6, AP_OADatabase, _radius_min, 0.01f),9293// @Param: DIST_MAX94// @DisplayName: OADatabase Distance Maximum95// @Description: Maximum distance of objects held in database. Set to zero to disable the limits96// @Units: m97// @Range: 0 1098// @User: Advanced99AP_GROUPINFO("DIST_MAX", 7, AP_OADatabase, _dist_max, 0.0f),100101// @Param{Copter}: ALT_MIN102// @DisplayName: OADatabase minimum altitude above home before storing obstacles103// @Description: OADatabase will reject obstacles if vehicle's altitude above home is below this parameter, in a 3 meter radius around home. Set 0 to disable this feature.104// @Units: m105// @Range: 0 4106// @User: Advanced107AP_GROUPINFO_FRAME("ALT_MIN", 8, AP_OADatabase, _min_alt, 0.0f, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),108109AP_GROUPEND110};111112AP_OADatabase::AP_OADatabase()113{114if (_singleton != nullptr) {115AP_HAL::panic("AP_OADatabase must be singleton");116}117_singleton = this;118119AP_Param::setup_object_defaults(this, var_info);120}121122void AP_OADatabase::init()123{124// PARAMETER_CONVERSION - Added: JUN-2025125_database_expiry_seconds.convert_parameter_width(AP_PARAM_INT8);126127init_database();128init_queue();129130// initialise scalar using beam width of at least 1deg131dist_to_radius_scalar = tanf(radians(MAX(_beam_width, 1.0f)));132133if (!healthy()) {134GCS_SEND_TEXT(MAV_SEVERITY_INFO, "DB init failed . Sizes queue:%u, db:%u", (unsigned int)_queue.size, (unsigned int)_database.size);135delete _queue.items;136delete[] _database.items;137return;138}139}140141void AP_OADatabase::update()142{143if (!healthy()) {144return;145}146147process_queue();148database_items_remove_all_expired();149}150151// Push an object into the database. Pos is the offset in meters from the EKF origin, measurement timestamp in ms, distance in meters152void AP_OADatabase::queue_push(const Vector3f &pos, const uint32_t timestamp_ms, const float distance, const OA_DbItem::Source source, const uint32_t id)153{154// Push with radius calculated from beam width155queue_push(pos, timestamp_ms, distance, distance * dist_to_radius_scalar, source, id);156}157158// Push an object into the database. Pos is the offset in meters from the EKF origin, measurement timestamp in ms, distance in meters, radius in meters159void AP_OADatabase::queue_push(const Vector3f &pos, const uint32_t timestamp_ms, const float distance, float radius, const OA_DbItem::Source source, const uint32_t id)160{161if (!healthy()) {162return;163}164165// check if this obstacle needs to be rejected from DB because of low altitude near home166#if APM_BUILD_COPTER_OR_HELI167if (!is_zero(_min_alt)) {168Vector3f current_pos;169if (!AP::ahrs().get_relative_position_NED_home(current_pos)) {170// we do not know where the vehicle is171return;172}173if (current_pos.xy().length() < AP_OADATABASE_DISTANCE_FROM_HOME) {174// vehicle is within a small radius of home175if (-current_pos.z < _min_alt) {176// vehicle is below the minimum alt177return;178}179}180}181#endif182183// Apply min radius parameter184radius = MAX(_radius_min, radius);185186// ignore objects that outside of the max distance187if (is_positive(_dist_max)) {188const float closest_point = distance - radius;189if (closest_point > _dist_max) {190return;191}192}193194const OA_DbItem item = {pos, timestamp_ms, radius, id, 0, AP_OADatabase::OA_DbItemImportance::Normal, source};195{196WITH_SEMAPHORE(_queue.sem);197_queue.items->push(item);198}199}200201void AP_OADatabase::init_queue()202{203_queue.size = _queue_size_param;204if (_queue.size == 0) {205return;206}207208_queue.items = NEW_NOTHROW ObjectBuffer<OA_DbItem>(_queue.size);209if (_queue.items != nullptr && _queue.items->get_size() == 0) {210// allocation failed211delete _queue.items;212_queue.items = nullptr;213}214}215216void AP_OADatabase::init_database()217{218_database.size = _database_size_param;219if (_database_size_param == 0) {220return;221}222223_database.items = NEW_NOTHROW OA_DbItem[_database.size];224}225226// get bitmask of gcs channels item should be sent to based on its importance227// returns 0xFF (send to all channels) if should be sent, 0 if it should not be sent228uint8_t AP_OADatabase::get_send_to_gcs_flags(const OA_DbItemImportance importance) const229{230switch (importance) {231case OA_DbItemImportance::Low:232if (_output_level >= OutputLevel::ALL) {233return 0xFF;234}235break;236237case OA_DbItemImportance::Normal:238if (_output_level >= OutputLevel::HIGH_AND_NORMAL) {239return 0xFF;240}241break;242243case OA_DbItemImportance::High:244if (_output_level >= OutputLevel::HIGH) {245return 0xFF;246}247break;248}249return 0x0;250}251252// Return true if item A is likely the same as item B253bool AP_OADatabase::item_match(const OA_DbItem& A, const OA_DbItem& B) const254{255// Items must be from the same source to match256if (A.source != B.source) {257return false;258}259260switch (A.source) {261case OA_DbItem::Source::AIS:262// Check IDs263return A.id == B.id;264265case OA_DbItem::Source::proximity:266// Check if close267const float distance_sq = (A.pos - B.pos).length_squared();268return distance_sq < sq(MAX(A.radius, B.radius));269}270271return false;272}273274// returns true when there's more work in the queue to do275bool AP_OADatabase::process_queue()276{277if (!healthy()) {278return false;279}280281// processing queue by moving those entries into the database282// Using a for with fixed size is better than while(!empty) because the283// while could get us stuck here longer than expected if we're getting284// a lot of values pushing into it while we're trying to empty it. With285// the for we know we will exit at an expected time286const uint16_t queue_available = MIN(_queue.items->available(), 100U);287if (queue_available == 0) {288return false;289}290291for (uint16_t queue_index=0; queue_index<queue_available; queue_index++) {292OA_DbItem item;293294bool pop_success;295{296WITH_SEMAPHORE(_queue.sem);297pop_success = _queue.items->pop(item);298}299if (!pop_success) {300return false;301}302303item.send_to_gcs = get_send_to_gcs_flags(item.importance);304305// compare item to all items in database. If found a similar item, update the existing, else add it as a new one306bool found = false;307for (uint16_t i=0; i<_database.count; i++) {308if (item_match(_database.items[i], item)) {309database_item_refresh(_database.items[i], item);310found = true;311break;312}313}314315if (!found) {316database_item_add(item);317}318}319return (_queue.items->available() > 0);320}321322void AP_OADatabase::database_item_add(const OA_DbItem &item)323{324if (_database.count >= _database.size) {325return;326}327_database.items[_database.count] = item;328_database.items[_database.count].send_to_gcs = get_send_to_gcs_flags(_database.items[_database.count].importance);329_database.count++;330}331332void AP_OADatabase::database_item_remove(const uint16_t index)333{334if (index >= _database.count || _database.count == 0) {335// index out of range336return;337}338339// radius of 0 tells the GCS we don't care about it any more (aka it expired)340_database.items[index].radius = 0;341_database.items[index].send_to_gcs = get_send_to_gcs_flags(_database.items[index].importance);342343_database.count--;344if (_database.count == 0) {345return;346}347348if (index != _database.count) {349// copy last object in array over expired object350_database.items[index] = _database.items[_database.count];351_database.items[index].send_to_gcs = get_send_to_gcs_flags(_database.items[index].importance);352}353}354355void AP_OADatabase::database_item_refresh(OA_DbItem ¤t_item, const OA_DbItem &new_item) const356{357const bool is_different =358(!is_equal(current_item.radius, new_item.radius)) ||359(new_item.timestamp_ms - current_item.timestamp_ms >= 500);360361if (is_different) {362// update timestamp and radius on close object so it stays around longer363// and trigger resending to GCS364current_item.timestamp_ms = new_item.timestamp_ms;365current_item.radius = new_item.radius;366current_item.send_to_gcs = get_send_to_gcs_flags(current_item.importance);367368if (current_item.source == OA_DbItem::Source::AIS) {369// Update position for AIS items, these tend to be large and update slowly370current_item.pos = new_item.pos;371}372}373}374375void AP_OADatabase::database_items_remove_all_expired()376{377// calculate age of all items in the _database378379if (_database_expiry_seconds <= 0) {380// zero means never expire. This is not normal behavior but perhaps you could send a static381// environment once that you don't want to have to constantly update382return;383}384385const uint32_t now_ms = AP_HAL::millis();386const uint32_t expiry_ms = (uint32_t)_database_expiry_seconds * 1000;387uint16_t index = 0;388while (index < _database.count) {389if (now_ms - _database.items[index].timestamp_ms > expiry_ms) {390database_item_remove(index);391} else {392index++;393}394}395}396397#if HAL_GCS_ENABLED398// send ADSB_VEHICLE mavlink messages399void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms)400{401// ensure database's send_to_gcs field is large enough402static_assert(MAVLINK_COMM_NUM_BUFFERS <= sizeof(OA_DbItem::send_to_gcs) * 8,403"AP_OADatabase's OA_DBItem.send_to_gcs bitmask must be large enough to hold MAVLINK_COMM_NUM_BUFFERS");404405if ((_output_level <= OutputLevel::NONE) || !healthy()) {406return;407}408409const uint8_t chan_as_bitmask = 1 << chan;410const char callsign[9] = "OA_DB";411412// calculate how many messages we should send413const uint32_t now_ms = AP_HAL::millis();414uint16_t num_to_send = 1;415uint16_t num_sent = 0;416if ((_last_send_to_gcs_ms[chan] != 0) && (interval_ms > 0)) {417uint32_t diff_ms = now_ms - _last_send_to_gcs_ms[chan];418num_to_send = MAX(diff_ms / interval_ms, 1U);419}420_last_send_to_gcs_ms[chan] = now_ms;421422// send unsent objects until output buffer is full or have sent enough423for (uint16_t i=0; i < _database.count; i++) {424if (!HAVE_PAYLOAD_SPACE(chan, ADSB_VEHICLE) || (num_sent >= num_to_send)) {425// all done for now426return;427}428429const uint16_t idx = _next_index_to_send[chan];430431// prepare to send next object432_next_index_to_send[chan]++;433if (_next_index_to_send[chan] >= _database.count) {434_next_index_to_send[chan] = 0;435}436437if ((_database.items[idx].send_to_gcs & chan_as_bitmask) == 0) {438continue;439}440441// convert object's position as an offset from EKF origin to Location442const Location item_loc(Vector3f{_database.items[idx].pos.x * 100.0f, _database.items[idx].pos.y * 100.0f, _database.items[idx].pos.z * 100.0f}, Location::AltFrame::ABOVE_ORIGIN);443444mavlink_msg_adsb_vehicle_send(chan,445idx,446item_loc.lat,447item_loc.lng,4480, // altitude_type449item_loc.alt,4500, // heading4510, // hor_velocity4520, // ver_velocity453callsign, // callsign454255, // emitter_type4550, // tslc4560, // flags457(uint16_t)(_database.items[idx].radius * 100.f)); // squawk458459// unmark item for sending to gcs460_database.items[idx].send_to_gcs &= ~chan_as_bitmask;461462// update highest index sent to GCS463_highest_index_sent[chan] = MAX(idx, _highest_index_sent[chan]);464465// update count sent466num_sent++;467}468469// clear expired items in case the database size shrank470while (_highest_index_sent[chan] > _database.count) {471if (!HAVE_PAYLOAD_SPACE(chan, ADSB_VEHICLE) || (num_sent >= num_to_send)) {472// all done for now473return;474}475476const uint16_t idx = _highest_index_sent[chan];477_highest_index_sent[chan]--;478479if (_database.items[idx].importance != OA_DbItemImportance::High) {480continue;481}482483mavlink_msg_adsb_vehicle_send(chan,484idx, // id4850, // latitude4860, // longitude4870, // altitude_type4880, // altitude4890, // heading4900, // hor_velocity4910, // ver_velocity492callsign, // callsign493255, // emitter_type4940, // tslc4950, // flags4960); // squawk497498// update count sent499num_sent++;500}501}502#endif // HAL_GCS_ENABLED503504// singleton instance505AP_OADatabase *AP_OADatabase::_singleton;506507namespace AP {508AP_OADatabase *oadatabase()509{510return AP_OADatabase::get_singleton();511}512513}514515#endif // AP_OADATABASE_ENABLED516517518