APM:Libraries
AP_ADSB.cpp
Go to the documentation of this file.
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 
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 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  AP_ADSB.cpp
18 
19  ADS-B RF based collision avoidance module
20  https://en.wikipedia.org/wiki/Automatic_dependent_surveillance_%E2%80%93_broadcast
21 */
22 
23 #include <AP_HAL/AP_HAL.h>
24 #include "AP_ADSB.h"
26 #include <stdio.h> // for sprintf
27 #include <limits.h>
28 #include <AP_Vehicle/AP_Vehicle.h>
29 #include <GCS_MAVLink/GCS.h>
30 
31 #define VEHICLE_TIMEOUT_MS 5000 // if no updates in this time, drop it from the list
32 #define ADSB_VEHICLE_LIST_SIZE_DEFAULT 25
33 #define ADSB_VEHICLE_LIST_SIZE_MAX 100
34 #define ADSB_CHAN_TIMEOUT_MS 15000
35 #define ADSB_SQUAWK_OCTAL_DEFAULT 1200
36 
37 #define ADSB_BITBASK_RF_CAPABILITIES_UAT_IN (1 << 0)
38 #define ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN (1 << 1)
39 
40 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
41  #define ADSB_LIST_RADIUS_DEFAULT 10000 // in meters
42 #else // APM_BUILD_TYPE(APM_BUILD_ArduCopter), Rover, Boat
43  #define ADSB_LIST_RADIUS_DEFAULT 2000 // in meters
44 #endif
45 
46 extern const AP_HAL::HAL& hal;
47 
48 // table of user settable parameters
50  // @Param: ENABLE
51  // @DisplayName: Enable ADSB
52  // @Description: Enable ADS-B
53  // @Values: 0:Disabled,1:Enabled
54  // @User: Standard
55  AP_GROUPINFO_FLAGS("ENABLE", 0, AP_ADSB, _enabled, 0, AP_PARAM_FLAG_ENABLE),
56 
57  // index 1 is reserved - was BEHAVIOR
58 
59  // @Param: LIST_MAX
60  // @DisplayName: ADSB vehicle list size
61  // @Description: ADSB list size of nearest vehicles. Longer lists take longer to refresh with lower SRx_ADSB values.
62  // @Range: 1 100
63  // @User: Advanced
65 
66 
67  // @Param: LIST_RADIUS
68  // @DisplayName: ADSB vehicle list radius filter
69  // @Description: ADSB vehicle list radius filter. Vehicles detected outside this radius will be completely ignored. They will not show up in the SRx_ADSB stream to the GCS and will not be considered in any avoidance calculations.
70  // @Range: 1 100000
71  // @User: Advanced
72  AP_GROUPINFO("LIST_RADIUS", 3, AP_ADSB, in_state.list_radius, ADSB_LIST_RADIUS_DEFAULT),
73 
74  // @Param: ICAO_ID
75  // @DisplayName: ICAO_ID vehicle identification number
76  // @Description: ICAO_ID unique vehicle identification number of this aircraft. This is a integer limited to 24bits. If set to 0 then one will be randomly generated. If set to -1 then static information is not sent, transceiver is assumed pre-programmed.
77  // @Range: -1 16777215
78  // @User: Advanced
79  AP_GROUPINFO("ICAO_ID", 4, AP_ADSB, out_state.cfg.ICAO_id_param, 0),
80 
81  // @Param: EMIT_TYPE
82  // @DisplayName: Emitter type
83  // @Description: ADSB classification for the type of vehicle emitting the transponder signal. Default value is 14 (UAV).
84  // @Values: 0:NoInfo,1:Light,2:Small,3:Large,4:HighVortexlarge,5:Heavy,6:HighlyManuv,7:Rotocraft,8:RESERVED,9:Glider,10:LightAir,11:Parachute,12:UltraLight,13:RESERVED,14:UAV,15:Space,16:RESERVED,17:EmergencySurface,18:ServiceSurface,19:PointObstacle
85  // @User: Advanced
86  AP_GROUPINFO("EMIT_TYPE", 5, AP_ADSB, out_state.cfg.emitterType, ADSB_EMITTER_TYPE_UAV),
87 
88  // @Param: LEN_WIDTH
89  // @DisplayName: Aircraft length and width
90  // @Description: Aircraft length and width dimension options in Length and Width in meters. In most cases, use a value of 1 for smallest size.
91  // @Values: 0:NO_DATA,1:L15W23,2:L25W28P5,3:L25W34,4:L35W33,5:L35W38,6:L45W39P5,7:L45W45,8:L55W45,9:L55W52,10:L65W59P5,11:L65W67,12:L75W72P5,13:L75W80,14:L85W80,15:L85W90
92  // @User: Advanced
93  AP_GROUPINFO("LEN_WIDTH", 6, AP_ADSB, out_state.cfg.lengthWidth, UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M),
94 
95  // @Param: OFFSET_LAT
96  // @DisplayName: GPS antenna lateral offset
97  // @Description: GPS antenna lateral offset. This describes the physical location offest from center of the GPS antenna on the aircraft.
98  // @Values: 0:NoData,1:Left2m,2:Left4m,3:Left6m,4:Center,5:Right2m,6:Right4m,7:Right6m
99  // @User: Advanced
100  AP_GROUPINFO("OFFSET_LAT", 7, AP_ADSB, out_state.cfg.gpsLatOffset, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M),
101 
102  // @Param: OFFSET_LON
103  // @DisplayName: GPS antenna longitudinal offset
104  // @Description: GPS antenna longitudinal offset. This is usually set to 1, Applied By Sensor
105  // @Values: 0:NO_DATA,1:AppliedBySensor
106  // @User: Advanced
107  AP_GROUPINFO("OFFSET_LON", 8, AP_ADSB, out_state.cfg.gpsLonOffset, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR),
108 
109  // @Param: RF_SELECT
110  // @DisplayName: Transceiver RF selection
111  // @Description: Transceiver RF selection for Rx enable and/or Tx enable. This only effects devices that can Tx and Rx. Rx-only devices override this to always be Rx-only.
112  // @Values: 0:Disabled,1:Rx-Only,2:Tx-Only,3:Rx and Tx Enabled
113  // @User: Advanced
114  AP_GROUPINFO("RF_SELECT", 9, AP_ADSB, out_state.cfg.rfSelect, UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED),
115 
116  // @Param: SQUAWK
117  // @DisplayName: Squawk code
118  // @Description: VFR squawk (Mode 3/A) code is a pre-programmed default code when the pilot is flying VFR and not in contact with ATC. In the USA, the VFR squawk code is octal 1200 (hex 0x280, decimal 640) and in most parts of Europe the VFR squawk code is octal 7000. If an invalid octal number is set then it will be reset to 1200.
119  // @Units: octal
120  // @User: Advanced
121  AP_GROUPINFO("SQUAWK", 10, AP_ADSB, out_state.cfg.squawk_octal_param, ADSB_SQUAWK_OCTAL_DEFAULT),
122 
123  // @Param: RF_CAPABLE
124  // @DisplayName: RF capabilities
125  // @Description: Describes your hardware RF In/Out capabilities.
126  // @Values: 0:Unknown,1:Rx UAT only,3:Rx UAT and 1090ES,7:Rx&Tx UAT and 1090ES
127  // @Bitmask: 0:UAT_in,1:1090ES_in,2:UAT_out,3:1090ES_out
128  // @User: Advanced
129  AP_GROUPINFO("RF_CAPABLE", 11, AP_ADSB, out_state.cfg.rf_capable, 0),
130 
131 
133 };
134 
135 /*
136  * Initialize variables and allocate memory for array
137  */
138 void AP_ADSB::init(void)
139 {
140  // in_state
141  in_state.vehicle_count = 0;
142  if (in_state.vehicle_list == nullptr) {
143  if (in_state.list_size_param != constrain_int16(in_state.list_size_param, 1, ADSB_VEHICLE_LIST_SIZE_MAX)) {
144  in_state.list_size_param.set_and_notify(ADSB_VEHICLE_LIST_SIZE_DEFAULT);
145  in_state.list_size_param.save();
146  }
147  in_state.list_size = in_state.list_size_param;
148  in_state.vehicle_list = new adsb_vehicle_t[in_state.list_size];
149 
150  if (in_state.vehicle_list == nullptr) {
151  // dynamic RAM allocation of _vehicle_list[] failed, disable gracefully
152  hal.console->printf("Unable to initialize ADS-B vehicle list\n");
153  _enabled.set_and_notify(0);
154  }
155  }
156 
159 
160  // out_state
161  set_callsign("PING1234", false);
162 }
163 
164 /*
165  * de-initialize and free up some memory
166  */
167 void AP_ADSB::deinit(void)
168 {
169  in_state.vehicle_count = 0;
170  if (in_state.vehicle_list != nullptr) {
171  delete [] in_state.vehicle_list;
172  in_state.vehicle_list = nullptr;
173  }
174 }
175 
176 /*
177  * periodic update to handle vehicle timeouts and trigger collision detection
178  */
179 void AP_ADSB::update(void)
180 {
181  // update _my_loc
182  if (!AP::ahrs().get_position(_my_loc)) {
183  _my_loc.zero();
184  }
185 
186  if (!_enabled) {
187  if (in_state.vehicle_list != nullptr) {
188  deinit();
189  }
190  // nothing to do
191  return;
192  } else if (in_state.vehicle_list == nullptr) {
193  init();
194  return;
195  } else if (in_state.list_size != in_state.list_size_param) {
196  deinit();
197  return;
198  }
199 
200  uint32_t now = AP_HAL::millis();
201 
202  // check current list for vehicles that time out
203  uint16_t index = 0;
204  while (index < in_state.vehicle_count) {
205  // check list and drop stale vehicles. When disabled, the list will get flushed
206  if (now - in_state.vehicle_list[index].last_update_ms > VEHICLE_TIMEOUT_MS) {
207  // don't increment index, we want to check this same index again because the contents changed
208  // also, if we're disabled then clear the list
209  delete_vehicle(index);
210  } else {
211  index++;
212  }
213  }
214 
215  if (_my_loc.is_zero()) {
216  // if we don't have a GPS lock then there's nothing else to do
217  return;
218  }
219 
220  if (out_state.chan < 0) {
221  // if there's no transceiver detected then do not set ICAO and do not service the transceiver
222  return;
223  }
224 
225 
226  if (out_state.cfg.squawk_octal_param != out_state.cfg.squawk_octal) {
227  // param changed, check that it's a valid octal
228  if (!is_valid_octal(out_state.cfg.squawk_octal_param)) {
229  // invalid, reset it to default
230  out_state.cfg.squawk_octal_param = ADSB_SQUAWK_OCTAL_DEFAULT;
231  }
232  out_state.cfg.squawk_octal = (uint16_t)out_state.cfg.squawk_octal_param;
233  }
234 
235  // ensure it's positive 24bit but allow -1
236  if (out_state.cfg.ICAO_id_param <= -1 || out_state.cfg.ICAO_id_param > 0x00FFFFFF) {
237  // icao param of -1 means static information is not sent, transceiver is assumed pre-programmed.
238  // reset timer constantly so it never reaches 10s so it never sends
239  out_state.last_config_ms = now;
240 
241  } else if (out_state.cfg.ICAO_id == 0 ||
242  out_state.cfg.ICAO_id_param_prev != out_state.cfg.ICAO_id_param) {
243 
244  // if param changed then regenerate. This allows the param to be changed back to zero to trigger a re-generate
245  if (out_state.cfg.ICAO_id_param == 0) {
246  out_state.cfg.ICAO_id = genICAO(_my_loc);
247  } else {
248  out_state.cfg.ICAO_id = out_state.cfg.ICAO_id_param;
249  }
250  out_state.cfg.ICAO_id_param_prev = out_state.cfg.ICAO_id_param;
251  set_callsign("PING", true);
252  gcs().send_text(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", out_state.cfg.ICAO_id, out_state.cfg.callsign);
253  out_state.last_config_ms = 0; // send now
254  }
255 
256 
257  // send static configuration data to transceiver, every 5s
258  if (out_state.chan_last_ms > 0 && now - out_state.chan_last_ms > ADSB_CHAN_TIMEOUT_MS) {
259  // haven't gotten a heartbeat health status packet in a while, assume hardware failure
260  // TODO: reset out_state.chan
261  out_state.chan = -1;
262  gcs().send_text(MAV_SEVERITY_ERROR, "ADSB: Transceiver heartbeat timed out");
263  } else if (out_state.chan < MAVLINK_COMM_NUM_BUFFERS) {
264  mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + out_state.chan);
265  if (now - out_state.last_config_ms >= 5000 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_CFG)) {
266  out_state.last_config_ms = now;
267  send_configure(chan);
268  } // last_config_ms
269 
270  // send dynamic data to transceiver at 5Hz
271  if (now - out_state.last_report_ms >= 200 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_DYNAMIC)) {
272  out_state.last_report_ms = now;
273  send_dynamic_out(chan);
274  } // last_report_ms
275  } // chan_last_ms
276 }
277 
278 /*
279  * determine index and distance of furthest vehicle. This is
280  * used to bump it off when a new closer aircraft is detected
281  */
283 {
284  float max_distance = 0;
285  uint16_t max_distance_index = 0;
286 
287  for (uint16_t index = 0; index < in_state.vehicle_count; index++) {
288  float distance = _my_loc.get_distance(get_location(in_state.vehicle_list[index]));
289  if (max_distance < distance || index == 0) {
290  max_distance = distance;
291  max_distance_index = index;
292  }
293  } // for index
294 
295  furthest_vehicle_index = max_distance_index;
296  furthest_vehicle_distance = max_distance;
297 }
298 
299 /*
300  * Convert/Extract a Location from a vehicle
301  */
303 {
305  vehicle.info.lat,
306  vehicle.info.lon,
307  vehicle.info.altitude * 0.1f,
309 
310  return loc;
311 }
312 
313 /*
314  * delete a vehicle by copying last vehicle to
315  * current index then decrementing count
316  */
317 void AP_ADSB::delete_vehicle(const uint16_t index)
318 {
319  if (index < in_state.vehicle_count) {
320  // if the vehicle is the furthest, invalidate it. It has been bumped
324  }
325  if (index != (in_state.vehicle_count-1)) {
326  in_state.vehicle_list[index] = in_state.vehicle_list[in_state.vehicle_count-1];
327  }
328  // TODO: is memset needed? When we decrement the index we essentially forget about it
329  memset(&in_state.vehicle_list[in_state.vehicle_count-1], 0, sizeof(adsb_vehicle_t));
330  in_state.vehicle_count--;
331  }
332 }
333 
334 /*
335  * Search _vehicle_list for the given vehicle. A match
336  * depends on ICAO_address. Returns true if match found
337  * and index is populated. otherwise, return false.
338  */
339 bool AP_ADSB::find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const
340 {
341  for (uint16_t i = 0; i < in_state.vehicle_count; i++) {
342  if (in_state.vehicle_list[i].info.ICAO_address == vehicle.info.ICAO_address) {
343  *index = i;
344  return true;
345  }
346  }
347  return false;
348 }
349 
350 /*
351  * Update the vehicle list. If the vehicle is already in the
352  * list then it will update it, otherwise it will be added.
353  */
354 void AP_ADSB::handle_vehicle(const mavlink_message_t* packet)
355 {
356  if (in_state.vehicle_list == nullptr) {
357  // We are only null when disabled. Updating is inhibited.
358  return;
359  }
360 
361  uint16_t index = in_state.list_size + 1; // initialize with invalid index
363  mavlink_msg_adsb_vehicle_decode(packet, &vehicle.info);
365  bool my_loc_is_zero = _my_loc.is_zero();
366  float my_loc_distance_to_vehicle = _my_loc.get_distance(vehicle_loc);
367  bool out_of_range = in_state.list_radius > 0 && !my_loc_is_zero && my_loc_distance_to_vehicle > in_state.list_radius;
368  bool is_tracked_in_list = find_index(vehicle, &index);
369  uint32_t now = AP_HAL::millis();
370 
371  // note the last time the receiver got a packet from the aircraft
372  vehicle.last_update_ms = now - (vehicle.info.tslc * 1000);
373 
374  const uint16_t required_flags_position = ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE;
375  const bool detected_ourself = (out_state.cfg.ICAO_id != 0) && ((uint32_t)out_state.cfg.ICAO_id == vehicle.info.ICAO_address);
376 
377  if (vehicle_loc.is_zero() ||
378  out_of_range ||
379  detected_ourself ||
380  (vehicle.info.ICAO_address > 0x00FFFFFF) || // ICAO address is 24bits, so ignore higher values.
381  !(vehicle.info.flags & required_flags_position) ||
382  now - vehicle.last_update_ms > VEHICLE_TIMEOUT_MS) {
383 
384  // vehicle is out of range or invalid lat/lng. If we're tracking it, delete from list. Otherwise ignore it.
385  if (is_tracked_in_list) {
386  delete_vehicle(index);
387  }
388  return;
389 
390  } else if (is_tracked_in_list) {
391 
392  // found, update it
393  set_vehicle(index, vehicle);
394 
395  } else if (in_state.vehicle_count < in_state.list_size) {
396 
397  // not found and there's room, add it to the end of the list
398  set_vehicle(in_state.vehicle_count, vehicle);
399  in_state.vehicle_count++;
400 
401  } else {
402  // buffer is full. if new vehicle is closer than furthest, replace furthest with new
403 
404  if (my_loc_is_zero) {
405  // nothing else to do
408 
409  } else {
410  if (furthest_vehicle_distance <= 0) {
411  // ensure this is populated
413  }
414 
415  if (my_loc_distance_to_vehicle < furthest_vehicle_distance) { // is closer than the furthest
416  // replace with the furthest vehicle
418 
419  // furthest_vehicle_index is now invalid because the vehicle was overwritten, need
420  // to run determine_furthest_aircraft() to determine a new one next time
423  }
424  }
425  } // if buffer full
426 
427  const uint16_t required_flags_avoidance =
428  ADSB_FLAGS_VALID_COORDS |
429  ADSB_FLAGS_VALID_ALTITUDE |
430  ADSB_FLAGS_VALID_HEADING |
431  ADSB_FLAGS_VALID_VELOCITY;
432 
433  if (vehicle.info.flags & required_flags_avoidance) {
434  push_sample(vehicle); // note that set_vehicle modifies vehicle
435  }
436 }
437 
438 /*
439  * Copy a vehicle's data into the list
440  */
441 void AP_ADSB::set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle)
442 {
443  if (index < in_state.list_size) {
444  in_state.vehicle_list[index] = vehicle;
445  }
446 }
447 
448 void AP_ADSB::send_adsb_vehicle(const mavlink_channel_t chan)
449 {
450  if (in_state.vehicle_list == nullptr || in_state.vehicle_count == 0) {
451  return;
452  }
453 
454  uint32_t now = AP_HAL::millis();
455 
456  if (in_state.send_index[chan] >= in_state.vehicle_count) {
457  // we've finished a list
458  if (now - in_state.send_start_ms[chan] < 1000) {
459  // too soon to start a new one
460  return;
461  } else {
462  // start new list
463  in_state.send_start_ms[chan] = now;
464  in_state.send_index[chan] = 0;
465  }
466  }
467 
468  if (in_state.send_index[chan] < in_state.vehicle_count) {
469  mavlink_adsb_vehicle_t vehicle = in_state.vehicle_list[in_state.send_index[chan]].info;
470  in_state.send_index[chan]++;
471 
472  mavlink_msg_adsb_vehicle_send(chan,
473  vehicle.ICAO_address,
474  vehicle.lat,
475  vehicle.lon,
476  vehicle.altitude_type,
477  vehicle.altitude,
478  vehicle.heading,
479  vehicle.hor_velocity,
480  vehicle.ver_velocity,
481  vehicle.callsign,
482  vehicle.emitter_type,
483  vehicle.tslc,
484  vehicle.flags,
485  vehicle.squawk);
486  }
487 }
488 
489 
490 void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan)
491 {
492  const AP_GPS &gps = AP::gps();
493  const Vector3f &gps_velocity = gps.velocity();
494 
495  const int32_t latitude = _my_loc.lat;
496  const int32_t longitude = _my_loc.lng;
497  const int32_t altGNSS = _my_loc.alt * 10; // convert cm to mm
498  const int16_t velVert = gps_velocity.z * 1E2; // convert m/s to cm/s
499  const int16_t nsVog = gps_velocity.x * 1E2; // convert m/s to cm/s
500  const int16_t ewVog = gps_velocity.y * 1E2; // convert m/s to cm/s
501  const uint8_t fixType = gps.status(); // this lines up perfectly with our enum
502  const uint8_t emStatus = 0; // TODO: implement this ENUM. no emergency = 0
503  const uint8_t numSats = gps.num_sats();
504  const uint16_t squawk = out_state.cfg.squawk_octal;
505 
506  uint32_t accHoriz = UINT_MAX;
507  float accHoriz_f;
508  if (gps.horizontal_accuracy(accHoriz_f)) {
509  accHoriz = accHoriz_f * 1E3; // convert m to mm
510  }
511 
512  uint16_t accVert = USHRT_MAX;
513  float accVert_f;
514  if (gps.vertical_accuracy(accVert_f)) {
515  accVert = accVert_f * 1E2; // convert m to cm
516  }
517 
518  uint16_t accVel = USHRT_MAX;
519  float accVel_f;
520  if (gps.speed_accuracy(accVel_f)) {
521  accVel = accVel_f * 1E3; // convert m/s to mm/s
522  }
523 
524  uint16_t state = 0;
525  if (out_state._is_in_auto_mode) {
526  state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED;
527  }
528  if (!out_state.is_flying) {
529  state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND;
530  }
531 
532  // TODO: confirm this sets utcTime correctly
533  const uint64_t gps_time = gps.time_epoch_usec();
534  const uint32_t utcTime = gps_time / 1000000ULL;
535 
536  const AP_Baro &baro = AP::baro();
537  int32_t altPres = INT_MAX;
538  if (baro.healthy()) {
539  // Altitude difference between sea level pressure and current pressure. Result in millimeters
540  altPres = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure()) * 1E3; // convert m to mm;
541  }
542 
543 
544 
545  mavlink_msg_uavionix_adsb_out_dynamic_send(
546  chan,
547  utcTime,
548  latitude,
549  longitude,
550  altGNSS,
551  fixType,
552  numSats,
553  altPres,
554  accHoriz,
555  accVert,
556  accVel,
557  velVert,
558  nsVog,
559  ewVog,
560  emStatus,
561  state,
562  squawk);
563 }
564 
565 
566 /*
567  * To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features
568  * This function will override the MSB byte of the 24bit ICAO address. To ensure an invalid >24bit ICAO is never broadcasted,
569  * this function is used to create the encoded verison without ever writing to the actual ICAO number. It's created on-demand
570  */
572 {
573  // utilize the upper unused 8bits of the icao with special flags.
574  // This encoding is required for uAvionix devices that break the MAVLink spec.
575 
576  // ensure the user assignable icao is 24 bits
577  uint32_t encoded_icao = (uint32_t)out_state.cfg.ICAO_id & 0x00FFFFFF;
578 
579  encoded_icao &= ~0x20000000; // useGnssAltitude should always be FALSE
580  encoded_icao |= 0x10000000; // csidLogic should always be TRUE
581 
582  //SIL/SDA are special fields that should be set to 0 with only expert user adjustment
583  encoded_icao &= ~0x03000000; // SDA should always be FALSE
584  encoded_icao &= ~0x0C000000; // SIL should always be FALSE
585 
586  return encoded_icao;
587 }
588 
589 /*
590  * To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features
591  * This function will override the usually-null ending char of the callsign. It always encodes the last byte [8], even if
592  * the callsign string is less than 9 chars and there are other zero-padded nulls.
593  */
595 {
596 // Encoding of the 8bit null char
597 // (LSB) - knots
598 // bit.1 - knots
599 // bit.2 - knots
600 // bit.3 - (unused)
601 // bit.4 - flag - ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN
602 // bit.5 - flag - ADSB_BITBASK_RF_CAPABILITIES_UAT_IN
603 // bit.6 - flag - 0 = callsign is treated as callsign, 1 = callsign is treated as flightPlanID/Squawk
604 // (MSB) - (unused)
605 
606  uint8_t encoded_null = 0;
607 
608  if (out_state.cfg.maxAircraftSpeed_knots <= 0) {
609  // not set or unknown. no bits set
610  } else if (out_state.cfg.maxAircraftSpeed_knots <= 75) {
611  encoded_null |= 0x01;
612  } else if (out_state.cfg.maxAircraftSpeed_knots <= 150) {
613  encoded_null |= 0x02;
614  } else if (out_state.cfg.maxAircraftSpeed_knots <= 300) {
615  encoded_null |= 0x03;
616  } else if (out_state.cfg.maxAircraftSpeed_knots <= 600) {
617  encoded_null |= 0x04;
618  } else if (out_state.cfg.maxAircraftSpeed_knots <= 1200) {
619  encoded_null |= 0x05;
620  } else {
621  encoded_null |= 0x06;
622  }
623 
624 
625  if (out_state.cfg.rf_capable & ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN) {
626  encoded_null |= 0x10;
627  }
628  if (out_state.cfg.rf_capable & ADSB_BITBASK_RF_CAPABILITIES_UAT_IN) {
629  encoded_null |= 0x20;
630  }
631 
632 
633  /*
634  If the user has an 8 digit flightPlanID assigned from a filed flight plan, this should be assigned to FlightPlanID, (assigned by remote app)
635  else if the user has an assigned squawk code from ATC this should be converted from 4 digit octal to 4 character alpha string and assigned to FlightPlanID,
636  else if a tail number is known it should be set to the tail number of the aircraft, (assigned by remote app)
637  else it should be left blank (all 0's)
638  */
639 
640  // using the above logic, we must always assign the squawk. once we get configured
641  // externally then get_encoded_callsign_null_char() stops getting called
642  snprintf(out_state.cfg.callsign, 5, "%04d", unsigned(out_state.cfg.squawk_octal));
643  memset(&out_state.cfg.callsign[4], 0, 5); // clear remaining 5 chars
644  encoded_null |= 0x40;
645 
646  return encoded_null;
647 }
648 
649 /*
650  * handle incoming packet UAVIONIX_ADSB_OUT_CFG.
651  * This allows a GCS to send cfg info through the autopilot to the ADSB hardware.
652  * This is done indirectly by reading and storing the packet and then another mechanism sends it out periodically
653  */
654 void AP_ADSB::handle_out_cfg(const mavlink_message_t* msg)
655 {
656  mavlink_uavionix_adsb_out_cfg_t packet {};
657  mavlink_msg_uavionix_adsb_out_cfg_decode(msg, &packet);
658 
659  out_state.cfg.was_set_externally = true;
660 
661  out_state.cfg.ICAO_id = packet.ICAO;
662  out_state.cfg.ICAO_id_param = out_state.cfg.ICAO_id_param_prev = packet.ICAO & 0x00FFFFFFFF;
663 
664  // May contain a non-null value at the end so accept it as-is with memcpy instead of strcpy
665  memcpy(out_state.cfg.callsign, packet.callsign, sizeof(out_state.cfg.callsign));
666 
667  out_state.cfg.emitterType = packet.emitterType;
668  out_state.cfg.lengthWidth = packet.aircraftSize;
669  out_state.cfg.gpsLatOffset = packet.gpsOffsetLat;
670  out_state.cfg.gpsLonOffset = packet.gpsOffsetLon;
671  out_state.cfg.rfSelect = packet.rfSelect;
672  out_state.cfg.stall_speed_cm = packet.stallSpeed;
673 
674  // guard against string with non-null end char
675  char c = out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1];
676  out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = 0;
677  gcs().send_text(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", out_state.cfg.ICAO_id, out_state.cfg.callsign);
678  out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = c;
679 
680  // send now
681  out_state.last_config_ms = 0;
682 }
683 
684 /*
685  * populate and send MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG
686  */
687 void AP_ADSB::send_configure(const mavlink_channel_t chan)
688 {
689  // MAVLink spec says the 9 byte callsign field is 8 byte string with 9th byte as null.
690  // Here we temporarily set some flags in that null char to signify the callsign
691  // may be a flightplanID instead
692  int8_t callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN];
693  uint32_t icao;
694 
695  memcpy(callsign, out_state.cfg.callsign, sizeof(out_state.cfg.callsign));
696 
697  if (out_state.cfg.was_set_externally) {
698  // take values as-is
699  icao = out_state.cfg.ICAO_id;
700  } else {
701  callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = (int8_t)get_encoded_callsign_null_char();
702  icao = get_encoded_icao();
703  }
704 
705  mavlink_msg_uavionix_adsb_out_cfg_send(
706  chan,
707  icao,
708  (const char*)callsign,
709  (uint8_t)out_state.cfg.emitterType,
710  (uint8_t)out_state.cfg.lengthWidth,
711  (uint8_t)out_state.cfg.gpsLatOffset,
712  (uint8_t)out_state.cfg.gpsLonOffset,
713  out_state.cfg.stall_speed_cm,
714  (uint8_t)out_state.cfg.rfSelect);
715 }
716 
717 /*
718  * this is a message from the transceiver reporting it's health. Using this packet
719  * we determine which channel is on so we don't have to send out_state to all channels
720  */
721 
722 void AP_ADSB::handle_transceiver_report(const mavlink_channel_t chan, const mavlink_message_t* msg)
723 {
724  mavlink_uavionix_adsb_transceiver_health_report_t packet {};
725  mavlink_msg_uavionix_adsb_transceiver_health_report_decode(msg, &packet);
726 
727  if (out_state.chan != chan) {
728  gcs().send_text(MAV_SEVERITY_DEBUG, "ADSB: Found transceiver on channel %d", chan);
729  }
730 
731  out_state.chan_last_ms = AP_HAL::millis();
732  out_state.chan = chan;
733  out_state.status = (UAVIONIX_ADSB_RF_HEALTH)packet.rfHealth;
734 }
735 
736 /*
737  @brief Generates pseudorandom ICAO from gps time, lat, and lon.
738  Reference: DO282B, 2.2.4.5.1.3.2
739 
740  Note gps.time is the number of seconds since UTC midnight
741 */
742 uint32_t AP_ADSB::genICAO(const Location_Class &loc)
743 {
744  // gps_time is not seconds since UTC midnight, but it is an equivalent random number
745  // TODO: use UTC time instead of GPS time
746  const AP_GPS &gps = AP::gps();
747  const uint64_t gps_time = gps.time_epoch_usec();
748 
749  uint32_t timeSum = 0;
750  uint32_t M3 = 4096 * (loc.lat & 0x00000FFF) + (loc.lng & 0x00000FFF);
751 
752  for (uint8_t i=0; i<24; i++) {
753  timeSum += (((gps_time & 0x00FFFFFF)>> i) & 0x00000001);
754  }
755  return( (timeSum ^ M3) & 0x00FFFFFF);
756 }
757 
758 // assign a string to out_state.cfg.callsign but ensure it's null terminated
759 void AP_ADSB::set_callsign(const char* str, const bool append_icao)
760 {
761  bool zero_char_pad = false;
762 
763  // clean slate
764  memset(out_state.cfg.callsign, 0, sizeof(out_state.cfg.callsign));
765 
766  // copy str to cfg.callsign but we can't use strncpy because we need
767  // to restrict values to only 'A' - 'Z' and '0' - '9' and pad
768  for (uint8_t i=0; i<sizeof(out_state.cfg.callsign)-1; i++) {
769  if (!str[i] || zero_char_pad) {
770  // finish early. Either pad the rest with zero char or null terminate and call it a day
771  if ((append_icao && i<4) || zero_char_pad) {
772  out_state.cfg.callsign[i] = '0';
773  zero_char_pad = true;
774  } else {
775  // already null terminated via memset so just stop
776  break;
777  }
778 
779  } else if (('A' <= str[i] && str[i] <= 'Z') ||
780  ('0' <= str[i] && str[i] <= '9')) {
781  // valid as-is
782  // spaces are also allowed but are handled in the last else
783  out_state.cfg.callsign[i] = str[i];
784 
785  } else if ('a' <= str[i] && str[i] <= 'z') {
786  // toupper()
787  out_state.cfg.callsign[i] = str[i] - ('a' - 'A');
788 
789  } else if (i == 0) {
790  // invalid, pad to char zero because first index can't be space
791  out_state.cfg.callsign[i] = '0';
792 
793  } else {
794  // invalid, pad with space
795  out_state.cfg.callsign[i] = ' ';
796  }
797  } // for i
798 
799  if (append_icao) {
800  snprintf(&out_state.cfg.callsign[4], 5, "%04X", unsigned(out_state.cfg.ICAO_id % 0x10000));
801  }
802 }
803 
804 
806 {
807  samples.push_back(vehicle);
808 }
809 
811 {
812  return samples.pop_front(vehicle);
813 }
814 
815 void AP_ADSB::handle_message(const mavlink_channel_t chan, const mavlink_message_t* msg)
816 {
817  switch (msg->msgid) {
818  case MAVLINK_MSG_ID_ADSB_VEHICLE:
819  handle_vehicle(msg);
820  break;
821  case MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT:
822  handle_transceiver_report(chan, msg);
823  break;
824 
825  case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG:
826  handle_out_cfg(msg);
827  break;
828 
829  case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC:
830  // unhandled, this is an outbound packet only
831  default:
832  break;
833  }
834 
835 }
struct AP_ADSB::@1 in_state
Definition: AP_GPS.h:48
void send_adsb_vehicle(mavlink_channel_t chan)
Definition: AP_ADSB.cpp:448
void determine_furthest_aircraft(void)
Definition: AP_ADSB.cpp:282
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
bool next_sample(adsb_vehicle_t &obstacle)
Definition: AP_ADSB.cpp:810
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
void set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle)
Definition: AP_ADSB.cpp:441
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
uint32_t get_encoded_icao(void)
Definition: AP_ADSB.cpp:571
AP_HAL::UARTDriver * console
Definition: HAL.h:110
void init()
Definition: AP_ADSB.cpp:138
uint8_t get_encoded_callsign_null_char(void)
Definition: AP_ADSB.cpp:594
Interface definition for the various Ground Control System.
#define ADSB_VEHICLE_LIST_SIZE_MAX
Definition: AP_ADSB.cpp:33
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void push_sample(adsb_vehicle_t &vehicle)
Definition: AP_ADSB.cpp:805
bool is_valid_octal(uint16_t octal)
Definition: AP_Math.cpp:241
GCS & gcs()
uint32_t genICAO(const Location_Class &loc)
Definition: AP_ADSB.cpp:742
#define ADSB_SQUAWK_OCTAL_DEFAULT
Definition: AP_ADSB.cpp:35
static void gps_time(uint16_t *time_week, uint32_t *time_week_ms)
Definition: sitl_gps.cpp:176
void handle_vehicle(const mavlink_message_t *msg)
Definition: AP_ADSB.cpp:354
#define ADSB_BITBASK_RF_CAPABILITIES_UAT_IN
Definition: AP_ADSB.cpp:37
void handle_transceiver_report(mavlink_channel_t chan, const mavlink_message_t *msg)
Definition: AP_ADSB.cpp:722
float distance
Definition: location.cpp:94
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
float get_altitude_difference(float base_pressure, float pressure) const
Definition: AP_Baro.cpp:271
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
bool is_zero(void)
Definition: Location.h:71
void handle_out_cfg(const mavlink_message_t *msg)
Definition: AP_ADSB.cpp:654
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
void set_callsign(const char *str, const bool append_icao)
Definition: AP_ADSB.cpp:759
#define HAVE_PAYLOAD_SPACE(chan, id)
Definition: GCS.h:28
void zero(void)
Definition: Location.h:73
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
const Vector3f & velocity(uint8_t instance) const
Definition: AP_GPS.h:224
int8_t chan
Definition: AP_ADSB.h:147
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
AP_Buffer< adsb_vehicle_t, max_samples > samples
Definition: AP_ADSB.h:180
bool speed_accuracy(uint8_t instance, float &sacc) const
Definition: AP_GPS.cpp:316
#define VEHICLE_TIMEOUT_MS
Definition: AP_ADSB.cpp:31
T y
Definition: vector3.h:67
static AP_Baro baro
Definition: ModuleTest.cpp:18
uint32_t millis()
Definition: system.cpp:157
#define SSL_AIR_PRESSURE
Definition: definitions.h:83
T z
Definition: vector3.h:67
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
static int state
Definition: Util.cpp:20
Location_Class get_location(const adsb_vehicle_t &vehicle) const
Definition: AP_ADSB.cpp:302
static DummyVehicle vehicle
Definition: AHRS_Test.cpp:35
struct AP_ADSB::@2 out_state
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
bool healthy(void) const
Definition: AP_Baro.h:52
float get_pressure(void) const
Definition: AP_Baro.h:59
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
uint16_t furthest_vehicle_index
Definition: AP_ADSB.h:176
Location_Class _my_loc
Definition: AP_ADSB.h:125
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
uint8_t num_sats(uint8_t instance) const
Definition: AP_GPS.h:260
float get_distance(const struct Location &loc2) const
Definition: Location.cpp:224
AP_Int8 _enabled
Definition: AP_ADSB.h:123
AP_Int32 list_radius
Definition: AP_ADSB.h:135
#define ADSB_CHAN_TIMEOUT_MS
Definition: AP_ADSB.cpp:34
#define ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN
Definition: AP_ADSB.cpp:38
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
uint64_t time_epoch_usec(uint8_t instance) const
Definition: AP_GPS.cpp:356
void send_configure(const mavlink_channel_t chan)
Definition: AP_ADSB.cpp:687
AP_Int16 list_size_param
Definition: AP_ADSB.h:131
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
void update(void)
Definition: AP_ADSB.cpp:179
static AP_GPS gps
Definition: AHRS_Test.cpp:22
#define ADSB_VEHICLE_LIST_SIZE_DEFAULT
Definition: AP_ADSB.cpp:32
float furthest_vehicle_distance
Definition: AP_ADSB.h:177
AP_Baro & baro()
Definition: AP_Baro.cpp:737
bool vertical_accuracy(uint8_t instance, float &vacc) const
Definition: AP_GPS.cpp:334
bool horizontal_accuracy(uint8_t instance, float &hacc) const
Definition: AP_GPS.cpp:325
#define ADSB_LIST_RADIUS_DEFAULT
Definition: AP_ADSB.cpp:43
void deinit()
Definition: AP_ADSB.cpp:167
#define AP_GROUPEND
Definition: AP_Param.h:121
void delete_vehicle(const uint16_t index)
Definition: AP_ADSB.cpp:317
T x
Definition: vector3.h:67