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