Path: blob/master/libraries/AC_Avoidance/AP_OADatabase.h
4182 views
#pragma once12#include "AC_Avoidance_config.h"34#if AP_OADATABASE_ENABLED56#include <AP_HAL/Semaphores.h>7#include <AP_Math/AP_Math.h>8#include <GCS_MAVLink/GCS_MAVLink.h>9#include <AP_Param/AP_Param.h>1011class AP_OADatabase {12public:1314AP_OADatabase();1516CLASS_NO_COPY(AP_OADatabase); /* Do not allow copies */1718// get singleton instance19static AP_OADatabase *get_singleton() {20return _singleton;21}2223enum OA_DbItemImportance : uint8_t {24Low,25Normal,26High,27};2829struct OA_DbItem {30Vector3f pos; // position of the object as an offset in meters from the EKF origin31uint32_t timestamp_ms; // system time that object was last updated32float radius; // objects radius in meters3334// Unique ID, assigned by the source, not used by all sources35uint32_t id;3637uint8_t send_to_gcs; // bitmask of mavlink comports to which details of this object should be sent38OA_DbItemImportance importance;3940// Source of item, refresh treats sources differently41enum class Source : uint8_t {42proximity,43AIS44} source;45};4647void init();48void update();4950// Push an object into the database. Pos is the offset in meters from the EKF origin, measurement timestamp in ms, distance in meters, optional radius in meters51void queue_push(const Vector3f &pos, const uint32_t timestamp_ms, const float distance, float radius, const OA_DbItem::Source source, const uint32_t id = 0);52void queue_push(const Vector3f &pos, const uint32_t timestamp_ms, const float distance, const OA_DbItem::Source source, const uint32_t id = 0);5354// returns true if database is healthy55bool healthy() const { return (_queue.items != nullptr) && (_database.items != nullptr); }5657// fetch an item in database. Undefined result when i >= _database.count.58const OA_DbItem& get_item(uint32_t i) const { return _database.items[i]; }5960// get number of items in the database61uint16_t database_count() const { return _database.count; }6263// empty queue and try and put into database. Return true if there's more work to do64bool process_queue();6566// send ADSB_VEHICLE mavlink messages67void send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms);6869static const struct AP_Param::GroupInfo var_info[];7071private:7273// initialise74void init_queue();75void init_database();7677// database item management78void database_item_add(const OA_DbItem &item);79void database_item_refresh(OA_DbItem ¤t_item, const OA_DbItem &new_item) const;80void database_item_remove(const uint16_t index);81void database_items_remove_all_expired();8283// get bitmask of gcs channels item should be sent to based on its importance84// returns 0xFF (send to all channels) if should be sent or 0 if it should not be sent85uint8_t get_send_to_gcs_flags(const OA_DbItemImportance importance) const;8687// Return true if item A is likely the same as item B88bool item_match(const OA_DbItem& A, const OA_DbItem& B) const;8990// enum for use with _OUTPUT parameter91enum class OutputLevel {92NONE = 0,93HIGH = 1,94HIGH_AND_NORMAL = 2,95ALL = 396};9798// parameters99AP_Int16 _queue_size_param; // queue size100AP_Int16 _database_size_param; // db size101AP_Int16 _database_expiry_seconds; // objects expire after this timeout102AP_Enum<OutputLevel> _output_level; // controls which items should be sent to GCS103AP_Float _beam_width; // beam width used when converting lidar readings to object radius104AP_Float _radius_min; // objects minimum radius (in meters)105AP_Float _dist_max; // objects maximum distance (in meters)106AP_Float _min_alt; // OADatabase minimum vehicle height check (in meters)107108struct {109ObjectBuffer<OA_DbItem> *items; // thread safe incoming queue of points from proximity sensor to be put into database110uint16_t size; // cached value of _queue_size_param.111HAL_Semaphore sem; // semaphore for multi-thread use of queue112} _queue;113float dist_to_radius_scalar; // scalar to convert the distance and beam width to an object radius114115struct {116OA_DbItem *items; // array of objects in the database117uint16_t count; // number of objects in the items array118uint16_t size; // cached value of _database_size_param that sticks after initialized119} _database;120121uint16_t _next_index_to_send[MAVLINK_COMM_NUM_BUFFERS]; // index of next object in _database to send to GCS122uint16_t _highest_index_sent[MAVLINK_COMM_NUM_BUFFERS]; // highest index in _database sent to GCS123uint32_t _last_send_to_gcs_ms[MAVLINK_COMM_NUM_BUFFERS];// system time that send_adsb_vehicle was last called124125static AP_OADatabase *_singleton;126};127128namespace AP {129AP_OADatabase *oadatabase();130};131132#endif // AP_OADATABASE_ENABLED133134135