AP_OADatabase.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include "AP_OADatabase.h"
  14. #if !HAL_MINIMIZE_FEATURES
  15. #include <AP_AHRS/AP_AHRS.h>
  16. #include <GCS_MAVLink/GCS.h>
  17. #include <AP_Math/AP_Math.h>
  18. extern const AP_HAL::HAL& hal;
  19. #ifndef AP_OADATABASE_TIMEOUT_SECONDS_DEFAULT
  20. #define AP_OADATABASE_TIMEOUT_SECONDS_DEFAULT 10
  21. #endif
  22. #ifndef AP_OADATABASE_SIZE_DEFAULT
  23. #define AP_OADATABASE_SIZE_DEFAULT 100
  24. #endif
  25. #ifndef AP_OADATABASE_QUEUE_SIZE_DEFAULT
  26. #define AP_OADATABASE_QUEUE_SIZE_DEFAULT 80
  27. #endif
  28. const AP_Param::GroupInfo AP_OADatabase::var_info[] = {
  29. // @Param: SIZE
  30. // @DisplayName: OADatabase maximum number of points
  31. // @Description: OADatabase maximum number of points. Set to 0 to disable the OA Database. Larger means more points but is more cpu intensive to process
  32. // @Range: 0 10000
  33. // @User: Advanced
  34. // @RebootRequired: True
  35. AP_GROUPINFO("SIZE", 1, AP_OADatabase, _database_size_param, AP_OADATABASE_SIZE_DEFAULT),
  36. // @Param: EXPIRE
  37. // @DisplayName: OADatabase item timeout
  38. // @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.
  39. // @Units: s
  40. // @Range: 0 127
  41. // @Increment: 1
  42. // @User: Advanced
  43. AP_GROUPINFO("EXPIRE", 2, AP_OADatabase, _database_expiry_seconds, AP_OADATABASE_TIMEOUT_SECONDS_DEFAULT),
  44. // @Param: QUEUE_SIZE
  45. // @DisplayName: OADatabase queue maximum number of points
  46. // @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.
  47. // @Range: 1 200
  48. // @User: Advanced
  49. // @RebootRequired: True
  50. AP_GROUPINFO("QUEUE_SIZE", 3, AP_OADatabase, _queue_size_param, AP_OADATABASE_QUEUE_SIZE_DEFAULT),
  51. // @Param: OUTPUT
  52. // @DisplayName: OADatabase output level
  53. // @Description: OADatabase output level to configure which database objects are sent to the ground station. All data is always available internally for avoidance algorithms.
  54. // @Values: 0:Disabled,1:Send only HIGH importance items,2:Send HIGH and NORMAL importance items,3:Send all items
  55. // @User: Advanced
  56. AP_GROUPINFO("OUTPUT", 4, AP_OADatabase, _output_level, (float)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_HIGH),
  57. AP_GROUPEND
  58. };
  59. AP_OADatabase::AP_OADatabase()
  60. {
  61. if (_singleton != nullptr) {
  62. AP_HAL::panic("AP_OADatabase must be singleton");
  63. }
  64. _singleton = this;
  65. AP_Param::setup_object_defaults(this, var_info);
  66. }
  67. void AP_OADatabase::init()
  68. {
  69. init_database();
  70. init_queue();
  71. if (!healthy()) {
  72. gcs().send_text(MAV_SEVERITY_INFO, "DB init failed . Sizes queue:%u, db:%u", (unsigned int)_queue.size, (unsigned int)_database.size);
  73. delete _queue.items;
  74. delete[] _database.items;
  75. return;
  76. }
  77. }
  78. void AP_OADatabase::update()
  79. {
  80. if (!healthy()) {
  81. return;
  82. }
  83. process_queue();
  84. optimize_db_filter();
  85. database_items_remove_all_expired();
  86. }
  87. // push a location into the database
  88. void AP_OADatabase::queue_push(const Location &loc, const uint32_t timestamp_ms, const float distance, const float angle)
  89. {
  90. if (!healthy()) {
  91. return;
  92. }
  93. AP_OADatabase::OA_DbItemImportance importance = AP_OADatabase::OA_DbItemImportance::Normal;
  94. if (distance <= 0 || angle < 0 || angle > 360) {
  95. // sanity check
  96. importance = AP_OADatabase::OA_DbItemImportance::Normal;
  97. } else if (distance < 10 && (angle > (360-10) || angle < 10)) {
  98. // far and directly in front +/- 10deg
  99. importance = AP_OADatabase::OA_DbItemImportance::High;
  100. } else if (distance < 5 && (angle > (360-30) || angle < 30)) {
  101. // kinda far and forward of us +/- 30deg
  102. importance = AP_OADatabase::OA_DbItemImportance::High;
  103. } else if (distance < 3 && (angle > (360-90) || angle < 90)) {
  104. // near and ahead +/- 90deg
  105. importance = AP_OADatabase::OA_DbItemImportance::High;
  106. } else if (distance < 1.5) {
  107. // very close anywhere
  108. importance = AP_OADatabase::OA_DbItemImportance::High;
  109. } else if (distance >= 10) {
  110. // really far away
  111. importance = AP_OADatabase::OA_DbItemImportance::Low;
  112. } else if (distance < 5 && (angle <= (360-90) || angle >= 90)) {
  113. // kinda far and behind us
  114. importance = AP_OADatabase::OA_DbItemImportance::Low;
  115. }
  116. const OA_DbItem item = {loc, timestamp_ms, 0, 0, importance};
  117. {
  118. WITH_SEMAPHORE(_queue.sem);
  119. _queue.items->push(item);
  120. }
  121. }
  122. void AP_OADatabase::init_queue()
  123. {
  124. _queue.size = _queue_size_param;
  125. if (_queue.size == 0) {
  126. return;
  127. }
  128. _queue.items = new ObjectBuffer<OA_DbItem>(_queue.size);
  129. }
  130. void AP_OADatabase::init_database()
  131. {
  132. _database.size = _database_size_param;
  133. if (_database_size_param == 0) {
  134. return;
  135. }
  136. _database.items = new OA_DbItem[_database.size];
  137. }
  138. void AP_OADatabase::optimize_db_filter()
  139. {
  140. // TODO: check database size and if we're getting full
  141. // we should grow the database size and/or increase
  142. // _database_filter_m so less objects go into it and let
  143. // the existing ones timeout naturally
  144. const float filter_m_backup = _database.filter_m;
  145. if (_database.count > (_database.size * 0.90f)) {
  146. // we're almost full, lets increase the filter size by requiring more
  147. // spacing between points so less things get put into the database
  148. _database.filter_m = MIN(_database.filter_m*_database.filter_grow_rate, _database.filter_max_m);
  149. } else if (_database.count < (_database.size * 0.85f)) {
  150. // we have some room, lets loosen the filter requirement (smaller object points) to allow more samples
  151. _database.filter_m = MAX(_database.filter_m*_database.filter_shrink_rate,_database.filter_min_m);
  152. }
  153. // recompute the the radius filters
  154. if (!is_equal(filter_m_backup,_database.filter_m)) {
  155. _radius_importance_low = MIN(_database.filter_m*4,_database.filter_max_m);
  156. _radius_importance_normal = _database.filter_m;
  157. _radius_importance_high = MAX(_database.filter_m*0.25,_database.filter_min_m);
  158. }
  159. }
  160. // get bitmask of gcs channels item should be sent to based on its importance
  161. // returns 0xFF (send to all channels) if should be sent, 0 if it should not be sent
  162. uint8_t AP_OADatabase::get_send_to_gcs_flags(const OA_DbItemImportance importance)
  163. {
  164. switch (importance) {
  165. case OA_DbItemImportance::Low:
  166. if (_output_level.get() >= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_ALL) {
  167. return 0xFF;
  168. }
  169. break;
  170. case OA_DbItemImportance::Normal:
  171. if (_output_level.get() >= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_HIGH_AND_NORMAL) {
  172. return 0xFF;
  173. }
  174. break;
  175. case OA_DbItemImportance::High:
  176. if (_output_level.get() >= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_SEND_HIGH) {
  177. return 0xFF;
  178. }
  179. break;
  180. }
  181. return 0x0;
  182. }
  183. float AP_OADatabase::get_radius(const OA_DbItemImportance importance)
  184. {
  185. switch (importance) {
  186. case OA_DbItemImportance::Low:
  187. return _radius_importance_low;
  188. default:
  189. case OA_DbItemImportance::Normal:
  190. return _radius_importance_normal;
  191. case OA_DbItemImportance::High:
  192. return _radius_importance_high;
  193. }
  194. }
  195. // returns true when there's more work inthe queue to do
  196. bool AP_OADatabase::process_queue()
  197. {
  198. if (!healthy()) {
  199. return false;
  200. }
  201. // processing queue by moving those entries into the database
  202. // Using a for with fixed size is better than while(!empty) because the
  203. // while could get us stuck here longer than expected if we're getting
  204. // a lot of values pushing into it while we're trying to empty it. With
  205. // the for we know we will exit at an expected time
  206. const uint16_t queue_available = MIN(_queue.items->available(), 100U);
  207. if (queue_available == 0) {
  208. return false;
  209. }
  210. for (uint16_t queue_index=0; queue_index<queue_available; queue_index++) {
  211. OA_DbItem item;
  212. bool pop_success;
  213. {
  214. WITH_SEMAPHORE(_queue.sem);
  215. pop_success = _queue.items->pop(item);
  216. }
  217. if (!pop_success) {
  218. return false;
  219. }
  220. item.radius = get_radius(item.importance);
  221. item.send_to_gcs = get_send_to_gcs_flags(item.importance);
  222. // compare item to all items in database. If found a similar item, update the existing, else add it as a new one
  223. bool found = false;
  224. for (uint16_t i=0; i<_database.count; i++) {
  225. if (is_close_to_item_in_database(i, item)) {
  226. database_item_refresh(i, item.timestamp_ms, item.radius);
  227. found = true;
  228. break;
  229. }
  230. }
  231. if (!found) {
  232. database_item_add(item);
  233. }
  234. }
  235. return (_queue.items->available() > 0);
  236. }
  237. void AP_OADatabase::database_item_add(const OA_DbItem &item)
  238. {
  239. if (_database.count >= _database.size) {
  240. return;
  241. }
  242. _database.items[_database.count] = item;
  243. _database.items[_database.count].send_to_gcs = get_send_to_gcs_flags(_database.items[_database.count].importance);
  244. _database.count++;
  245. }
  246. void AP_OADatabase::database_item_remove(const uint16_t index)
  247. {
  248. if (index >= _database.count || _database.count == 0) {
  249. // index out of range
  250. return;
  251. }
  252. // radius of 0 tells the GCS we don't care about it any more (aka it expired)
  253. _database.items[index].radius = 0;
  254. _database.items[index].send_to_gcs = get_send_to_gcs_flags(_database.items[index].importance);
  255. _database.count--;
  256. if (_database.count == 0) {
  257. return;
  258. }
  259. if (index != _database.count) {
  260. // copy last object in array over expired object
  261. _database.items[index] = _database.items[_database.count];
  262. _database.items[index].send_to_gcs = get_send_to_gcs_flags(_database.items[index].importance);
  263. }
  264. }
  265. void AP_OADatabase::database_item_refresh(const uint16_t index, const uint32_t timestamp_ms, const float radius)
  266. {
  267. if (index >= _database.count) {
  268. // index out of range
  269. return;
  270. }
  271. const bool is_different =
  272. (!is_equal(_database.items[index].radius, radius)) ||
  273. (timestamp_ms - _database.items[index].timestamp_ms >= 500);
  274. if (is_different) {
  275. // update timestamp and radius on close object so it stays around longer
  276. // and trigger resending to GCS
  277. _database.items[index].timestamp_ms = timestamp_ms;
  278. _database.items[index].radius = radius;
  279. _database.items[index].send_to_gcs = get_send_to_gcs_flags(_database.items[index].importance);
  280. }
  281. }
  282. void AP_OADatabase::database_items_remove_all_expired()
  283. {
  284. // calculate age of all items in the _database
  285. if (_database_expiry_seconds <= 0) {
  286. // zero means never expire. This is not normal behavior but perhaps you could send a static
  287. // environment once that you don't want to have to constantly update
  288. return;
  289. }
  290. const uint32_t now_ms = AP_HAL::millis();
  291. const uint32_t expiry_ms = (uint32_t)_database_expiry_seconds * 1000;
  292. uint16_t index = 0;
  293. while (index < _database.count) {
  294. if (now_ms - _database.items[index].timestamp_ms > expiry_ms) {
  295. database_item_remove(index);
  296. } else {
  297. // overtime, the item radius will grow in size. If too big, remove it before the timer
  298. _database.items[index].radius *= _database.radius_grow_rate;
  299. if (_database.items[index].radius >= _database.filter_max_m) {
  300. database_item_remove(index);
  301. } else {
  302. index++;
  303. }
  304. }
  305. }
  306. }
  307. // returns true if a similar object already exists in database. When true, the object timer is also reset
  308. bool AP_OADatabase::is_close_to_item_in_database(const uint16_t index, const OA_DbItem &item) const
  309. {
  310. if (index >= _database.count) {
  311. // index out of range
  312. return false;
  313. }
  314. return (_database.items[index].loc.get_distance(item.loc) < item.radius);
  315. }
  316. // send ADSB_VEHICLE mavlink messages
  317. void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms)
  318. {
  319. // ensure database's send_to_gcs field is large enough
  320. static_assert(MAVLINK_COMM_NUM_BUFFERS <= sizeof(OA_DbItem::send_to_gcs) * 8,
  321. "AP_OADatabase's OA_DBItem.send_to_gcs bitmask must be large enough to hold MAVLINK_COMM_NUM_BUFFERS");
  322. if ((_output_level.get() <= (int8_t)OA_DbOutputLevel::OUTPUT_LEVEL_DISABLED) || !healthy()) {
  323. return;
  324. }
  325. const uint8_t chan_as_bitmask = 1 << chan;
  326. const char callsign[9] = "OA_DB";
  327. // calculate how many messages we should send
  328. const uint32_t now_ms = AP_HAL::millis();
  329. uint16_t num_to_send = 1;
  330. uint16_t num_sent = 0;
  331. if ((_last_send_to_gcs_ms[chan] != 0) && (interval_ms > 0)) {
  332. uint32_t diff_ms = now_ms - _last_send_to_gcs_ms[chan];
  333. num_to_send = MAX(diff_ms / interval_ms, 1U);
  334. }
  335. _last_send_to_gcs_ms[chan] = now_ms;
  336. // send unsent objects until output buffer is full or have sent enough
  337. for (uint16_t i=0; i < _database.count; i++) {
  338. if (!HAVE_PAYLOAD_SPACE(chan, ADSB_VEHICLE) || (num_sent >= num_to_send)) {
  339. // all done for now
  340. return;
  341. }
  342. const uint16_t idx = _next_index_to_send[chan];
  343. // prepare to send next object
  344. _next_index_to_send[chan]++;
  345. if (_next_index_to_send[chan] >= _database.count) {
  346. _next_index_to_send[chan] = 0;
  347. }
  348. if ((_database.items[idx].send_to_gcs & chan_as_bitmask) == 0) {
  349. continue;
  350. }
  351. mavlink_msg_adsb_vehicle_send(chan,
  352. idx,
  353. _database.items[idx].loc.lat,
  354. _database.items[idx].loc.lng,
  355. 0, // altitude_type
  356. _database.items[idx].loc.alt,
  357. 0, // heading
  358. 0, // hor_velocity
  359. 0, // ver_velocity
  360. callsign, // callsign
  361. 255, // emitter_type
  362. 0, // tslc
  363. 0, // flags
  364. (uint16_t)(_database.items[idx].radius * 100.f)); // squawk
  365. // unmark item for sending to gcs
  366. _database.items[idx].send_to_gcs &= ~chan_as_bitmask;
  367. // update highest index sent to GCS
  368. _highest_index_sent[chan] = MAX(idx, _highest_index_sent[chan]);
  369. // update count sent
  370. num_sent++;
  371. }
  372. // clear expired items in case the database size shrank
  373. while (_highest_index_sent[chan] > _database.count) {
  374. if (!HAVE_PAYLOAD_SPACE(chan, ADSB_VEHICLE) || (num_sent >= num_to_send)) {
  375. // all done for now
  376. return;
  377. }
  378. const uint16_t idx = _highest_index_sent[chan];
  379. _highest_index_sent[chan]--;
  380. if (_database.items[idx].importance != OA_DbItemImportance::High) {
  381. continue;
  382. }
  383. mavlink_msg_adsb_vehicle_send(chan,
  384. idx, // id
  385. 0, // latitude
  386. 0, // longitude
  387. 0, // altitude_type
  388. 0, // altitude
  389. 0, // heading
  390. 0, // hor_velocity
  391. 0, // ver_velocity
  392. callsign, // callsign
  393. 255, // emitter_type
  394. 0, // tslc
  395. 0, // flags
  396. 0); // squawk
  397. // update count sent
  398. num_sent++;
  399. }
  400. }
  401. // singleton instance
  402. AP_OADatabase *AP_OADatabase::_singleton;
  403. #endif //!HAL_MINIMIZE_FEATURES
  404. namespace AP {
  405. AP_OADatabase *oadatabase()
  406. {
  407. return AP_OADatabase::get_singleton();
  408. }
  409. }