AP_ADSB.h 7.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204
  1. #pragma once
  2. /*
  3. This program is free software: you can redistribute it and/or modify
  4. it under the terms of the GNU General Public License as published by
  5. the Free Software Foundation, either version 3 of the License, or
  6. (at your option) any later version.
  7. This program is distributed in the hope that it will be useful,
  8. but WITHOUT ANY WARRANTY; without even the implied warranty of
  9. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  10. GNU General Public License for more details.
  11. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. */
  14. /*
  15. ADS-B RF based collision avoidance module
  16. https://en.wikipedia.org/wiki/Automatic_dependent_surveillance_%E2%80%93_broadcast
  17. Tom Pittenger, November 2015
  18. */
  19. #include <AP_Common/AP_Common.h>
  20. #include <AP_Param/AP_Param.h>
  21. #include <AP_Common/Location.h>
  22. #include <GCS_MAVLink/GCS_MAVLink.h>
  23. #include <AP_Buffer/AP_Buffer.h>
  24. class AP_ADSB {
  25. public:
  26. AP_ADSB()
  27. {
  28. AP_Param::setup_object_defaults(this, var_info);
  29. }
  30. /* Do not allow copies */
  31. AP_ADSB(const AP_ADSB &other) = delete;
  32. AP_ADSB &operator=(const AP_ADSB&) = delete;
  33. struct adsb_vehicle_t {
  34. mavlink_adsb_vehicle_t info; // the whole mavlink struct with all the juicy details. sizeof() == 38
  35. uint32_t last_update_ms; // last time this was refreshed, allows timeouts
  36. };
  37. // for holding parameters
  38. static const struct AP_Param::GroupInfo var_info[];
  39. // periodic task that maintains vehicle_list
  40. void update(void);
  41. uint16_t get_vehicle_count() { return in_state.vehicle_count; }
  42. // send ADSB_VEHICLE mavlink message, usually as a StreamRate
  43. void send_adsb_vehicle(mavlink_channel_t chan);
  44. void set_stall_speed_cm(const uint16_t stall_speed_cm) { out_state.cfg.stall_speed_cm = stall_speed_cm; }
  45. void set_max_speed(int16_t max_speed) {
  46. if (!out_state.cfg.was_set_externally) {
  47. // convert m/s to knots
  48. out_state.cfg.maxAircraftSpeed_knots = (float)max_speed * 1.94384f;
  49. }
  50. }
  51. void set_is_auto_mode(const bool is_in_auto_mode) { out_state._is_in_auto_mode = is_in_auto_mode; }
  52. void set_is_flying(const bool is_flying) { out_state.is_flying = is_flying; }
  53. UAVIONIX_ADSB_RF_HEALTH get_transceiver_status(void) { return out_state.status; }
  54. // extract a location out of a vehicle item
  55. Location get_location(const adsb_vehicle_t &vehicle) const;
  56. bool enabled() const {
  57. return _enabled;
  58. }
  59. bool next_sample(adsb_vehicle_t &obstacle);
  60. // mavlink message handler
  61. void handle_message(const mavlink_channel_t chan, const mavlink_message_t &msg);
  62. // when true, a vehicle with that ICAO was found in database and the vehicle is populated.
  63. bool get_vehicle_by_ICAO(const uint32_t icao, adsb_vehicle_t &vehicle) const;
  64. uint32_t get_special_ICAO_target() const { return (uint32_t)_special_ICAO_target; };
  65. void set_special_ICAO_target(const uint32_t new_icao_target) { _special_ICAO_target = (int32_t)new_icao_target; };
  66. bool is_special_vehicle(uint32_t icao) const { return _special_ICAO_target != 0 && (_special_ICAO_target == (int32_t)icao); }
  67. private:
  68. // initialize _vehicle_list
  69. void init();
  70. // free _vehicle_list
  71. void deinit();
  72. // compares current vector against vehicle_list to detect threats
  73. void determine_furthest_aircraft(void);
  74. // return index of given vehicle if ICAO_ADDRESS matches. return -1 if no match
  75. bool find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const;
  76. // remove a vehicle from the list
  77. void delete_vehicle(const uint16_t index);
  78. void set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle);
  79. // Generates pseudorandom ICAO from gps time, lat, and lon
  80. uint32_t genICAO(const Location &loc);
  81. // set callsign: 8char string (plus null termination) then optionally append last 4 digits of icao
  82. void set_callsign(const char* str, const bool append_icao);
  83. // send static and dynamic data to ADSB transceiver
  84. void send_configure(const mavlink_channel_t chan);
  85. void send_dynamic_out(const mavlink_channel_t chan);
  86. // special helpers for uAvionix workarounds
  87. uint32_t get_encoded_icao(void);
  88. uint8_t get_encoded_callsign_null_char(void);
  89. // add or update vehicle_list from inbound mavlink msg
  90. void handle_vehicle(const mavlink_message_t &msg);
  91. // handle ADS-B transceiver report for ping2020
  92. void handle_transceiver_report(mavlink_channel_t chan, const mavlink_message_t &msg);
  93. void handle_out_cfg(const mavlink_message_t &msg);
  94. AP_Int8 _enabled;
  95. Location _my_loc;
  96. // ADSB-IN state. Maintains list of external vehicles
  97. struct {
  98. // list management
  99. AP_Int16 list_size_param;
  100. uint16_t list_size = 1; // start with tiny list, then change to param-defined size. This ensures it doesn't fail on start
  101. adsb_vehicle_t *vehicle_list = nullptr;
  102. uint16_t vehicle_count;
  103. AP_Int32 list_radius;
  104. AP_Int16 list_altitude;
  105. // streamrate stuff
  106. uint32_t send_start_ms[MAVLINK_COMM_NUM_BUFFERS];
  107. uint16_t send_index[MAVLINK_COMM_NUM_BUFFERS];
  108. } in_state;
  109. // ADSB-OUT state. Maintains export data
  110. struct {
  111. uint32_t last_config_ms; // send once every 10s
  112. uint32_t last_report_ms; // send at 5Hz
  113. int8_t chan = -1; // channel that contains an ADS-b Transceiver. -1 means transceiver is not detected
  114. uint32_t chan_last_ms;
  115. UAVIONIX_ADSB_RF_HEALTH status; // transceiver status
  116. bool is_flying;
  117. bool _is_in_auto_mode;
  118. // ADSB-OUT configuration
  119. struct {
  120. int32_t ICAO_id;
  121. AP_Int32 ICAO_id_param;
  122. int32_t ICAO_id_param_prev = -1; // assume we never send
  123. char callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN]; //Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, " " only).
  124. AP_Int8 emitterType;
  125. AP_Int8 lengthWidth; // Aircraft length and width encoding (table 2-35 of DO-282B)
  126. AP_Int8 gpsLatOffset;
  127. AP_Int8 gpsLonOffset;
  128. uint16_t stall_speed_cm;
  129. AP_Int8 rfSelect;
  130. AP_Int16 squawk_octal_param;
  131. uint16_t squawk_octal;
  132. float maxAircraftSpeed_knots;
  133. AP_Int8 rf_capable;
  134. bool was_set_externally;
  135. } cfg;
  136. } out_state;
  137. // index of and distance to furthest vehicle in list
  138. uint16_t furthest_vehicle_index;
  139. float furthest_vehicle_distance;
  140. // special ICAO of interest that ignored filters when != 0
  141. AP_Int32 _special_ICAO_target;
  142. static const uint8_t max_samples = 30;
  143. AP_Buffer<adsb_vehicle_t, max_samples> samples;
  144. void push_sample(adsb_vehicle_t &vehicle);
  145. // logging
  146. AP_Int8 _log;
  147. void write_log(const adsb_vehicle_t &vehicle);
  148. enum logging {
  149. NONE = 0,
  150. SPECIAL_ONLY = 1,
  151. ALL = 2
  152. };
  153. };