APM:Libraries
SIM_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  ADSB simulator class for MAVLink ADSB peripheral
17 */
18 
19 #include "SIM_ADSB.h"
20 #include "SITL.h"
21 
22 #include <stdio.h>
23 
24 #include "SIM_Aircraft.h"
25 
26 namespace SITL {
27 
29 
30 ADSB::ADSB(const struct sitl_fdm &_fdm, const char *_home_str)
31 {
32  float yaw_degrees;
33  Aircraft::parse_home(_home_str, home, yaw_degrees);
34 }
35 
36 
37 /*
38  update a simulated vehicle
39  */
40 void ADSB_Vehicle::update(float delta_t)
41 {
42  if (!initialised) {
43  initialised = true;
44  ICAO_address = (uint32_t)(rand() % 10000);
45  snprintf(callsign, sizeof(callsign), "SIM%u", ICAO_address);
46  position.x = Aircraft::rand_normal(0, _sitl->adsb_radius_m);
47  position.y = Aircraft::rand_normal(0, _sitl->adsb_radius_m);
48  position.z = -fabsf(_sitl->adsb_altitude_m);
49 
50  double vel_min = 5, vel_max = 20;
51  if (position.length() > 500) {
52  vel_min *= 3;
53  vel_max *= 3;
54  } else if (position.length() > 10000) {
55  vel_min *= 10;
56  vel_max *= 10;
57  }
58  velocity_ef.x = Aircraft::rand_normal(vel_min, vel_max);
59  velocity_ef.y = Aircraft::rand_normal(vel_min, vel_max);
60  velocity_ef.z = Aircraft::rand_normal(0, 3);
61  }
62 
63  position += velocity_ef * delta_t;
64  if (position.z > 0) {
65  // it has crashed! reset
66  initialised = false;
67  }
68 }
69 
70 /*
71  update the ADSB peripheral state
72 */
73 void ADSB::update(void)
74 {
75  if (_sitl == nullptr) {
76  _sitl = (SITL *)AP_Param::find_object("SIM_");
77  return;
78  } else if (_sitl->adsb_plane_count <= 0) {
79  return;
80  } else if (_sitl->adsb_plane_count >= num_vehicles_MAX) {
81  _sitl->adsb_plane_count.set_and_save(0);
82  num_vehicles = 0;
83  return;
84  } else if (num_vehicles != _sitl->adsb_plane_count) {
86  for (uint8_t i=0; i<num_vehicles_MAX; i++) {
87  vehicles[i].initialised = false;
88  }
89  }
90 
91  // calculate delta time in seconds
92  uint32_t now_us = AP_HAL::micros();
93 
94  float delta_t = (now_us - last_update_us) * 1.0e-6f;
95  last_update_us = now_us;
96 
97  for (uint8_t i=0; i<num_vehicles; i++) {
98  vehicles[i].update(delta_t);
99  }
100 
101  // see if we should do a report
102  send_report();
103 }
104 
105 /*
106  send a report to the vehicle control code over MAVLink
107 */
109 {
110  if (AP_HAL::millis() < 10000) {
111  // simulated aircraft don't appear until 10s after startup. This avoids a windows
112  // threading issue with non-blocking sockets and the initial wait on uartA
113  return;
114  }
115  if (!mavlink.connected && mav_socket.connect(target_address, target_port)) {
116  ::printf("ADSB connected to %s:%u\n", target_address, (unsigned)target_port);
117  mavlink.connected = true;
118  }
119  if (!mavlink.connected) {
120  return;
121  }
122 
123  // check for incoming MAVLink messages
124  uint8_t buf[100];
125  ssize_t ret;
126 
127  while ((ret=mav_socket.recv(buf, sizeof(buf), 0)) > 0) {
128  for (uint8_t i=0; i<ret; i++) {
129  mavlink_message_t msg;
130  mavlink_status_t status;
131  if (mavlink_frame_char_buffer(&mavlink.rxmsg, &mavlink.status,
132  buf[i],
133  &msg, &status) == MAVLINK_FRAMING_OK) {
134  switch (msg.msgid) {
135  case MAVLINK_MSG_ID_HEARTBEAT: {
136  if (!seen_heartbeat) {
137  seen_heartbeat = true;
138  vehicle_component_id = msg.compid;
139  vehicle_system_id = msg.sysid;
140  ::printf("ADSB using srcSystem %u\n", (unsigned)vehicle_system_id);
141  }
142  break;
143  }
144  }
145  }
146  }
147  }
148 
149  if (!seen_heartbeat) {
150  return;
151  }
152 
153  uint32_t now = AP_HAL::millis();
154  mavlink_message_t msg;
155  uint16_t len;
156 
157  if (now - last_heartbeat_ms >= 1000) {
158  mavlink_heartbeat_t heartbeat;
159  heartbeat.type = MAV_TYPE_ADSB;
160  heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
161  heartbeat.base_mode = 0;
162  heartbeat.system_status = 0;
163  heartbeat.mavlink_version = 0;
164  heartbeat.custom_mode = 0;
165 
166  /*
167  save and restore sequence number for chan0, as it is used by
168  generated encode functions
169  */
170  mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
171  uint8_t saved_seq = chan0_status->current_tx_seq;
172  chan0_status->current_tx_seq = mavlink.seq;
173  len = mavlink_msg_heartbeat_encode(vehicle_system_id,
175  &msg, &heartbeat);
176  chan0_status->current_tx_seq = saved_seq;
177 
178  mav_socket.send(&msg.magic, len);
179 
180  last_heartbeat_ms = now;
181  }
182 
183 
184  /*
185  send a ADSB_VEHICLE messages
186  */
187  uint32_t now_us = AP_HAL::micros();
188  if (now_us - last_report_us >= reporting_period_ms*1000UL) {
189  for (uint8_t i=0; i<num_vehicles; i++) {
191  Location loc = home;
192 
193  location_offset(loc, vehicle.position.x, vehicle.position.y);
194 
195  // re-init when exceeding radius range
196  if (get_distance(home, loc) > _sitl->adsb_radius_m) {
197  vehicle.initialised = false;
198  }
199 
200  mavlink_adsb_vehicle_t adsb_vehicle {};
201  last_report_us = now_us;
202 
203  adsb_vehicle.ICAO_address = vehicle.ICAO_address;
204  adsb_vehicle.lat = loc.lat;
205  adsb_vehicle.lon = loc.lng;
206  adsb_vehicle.altitude_type = ADSB_ALTITUDE_TYPE_PRESSURE_QNH;
207  adsb_vehicle.altitude = -vehicle.position.z * 1000;
208  adsb_vehicle.heading = wrap_360_cd(100*degrees(atan2f(vehicle.velocity_ef.y, vehicle.velocity_ef.x)));
209  adsb_vehicle.hor_velocity = norm(vehicle.velocity_ef.x, vehicle.velocity_ef.y) * 100;
210  adsb_vehicle.ver_velocity = -vehicle.velocity_ef.z * 100;
211  memcpy(adsb_vehicle.callsign, vehicle.callsign, sizeof(adsb_vehicle.callsign));
212  adsb_vehicle.emitter_type = ADSB_EMITTER_TYPE_LARGE;
213  adsb_vehicle.tslc = 1;
214  adsb_vehicle.flags =
215  ADSB_FLAGS_VALID_COORDS |
216  ADSB_FLAGS_VALID_ALTITUDE |
217  ADSB_FLAGS_VALID_HEADING |
218  ADSB_FLAGS_VALID_VELOCITY |
219  ADSB_FLAGS_VALID_CALLSIGN |
220  ADSB_FLAGS_SIMULATED;
221  adsb_vehicle.squawk = 0; // NOTE: ADSB_FLAGS_VALID_SQUAWK bit is not set
222 
223  mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
224  uint8_t saved_seq = chan0_status->current_tx_seq;
225  chan0_status->current_tx_seq = mavlink.seq;
226  len = mavlink_msg_adsb_vehicle_encode(vehicle_system_id,
227  MAV_COMP_ID_ADSB,
228  &msg, &adsb_vehicle);
229  chan0_status->current_tx_seq = saved_seq;
230 
231  uint8_t msgbuf[len];
232  len = mavlink_msg_to_send_buffer(msgbuf, &msg);
233  if (len > 0) {
234  mav_socket.send(msgbuf, len);
235  }
236  }
237  }
238 
239  // ADSB_transceiever is enabled, send the status report.
240  if (_sitl->adsb_tx && now - last_tx_report_ms > 1000) {
241  last_tx_report_ms = now;
242 
243  mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
244  uint8_t saved_seq = chan0_status->current_tx_seq;
245  uint8_t saved_flags = chan0_status->flags;
246  chan0_status->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
247  chan0_status->current_tx_seq = mavlink.seq;
248  const mavlink_uavionix_adsb_transceiver_health_report_t health_report = {UAVIONIX_ADSB_RF_HEALTH_OK};
249  len = mavlink_msg_uavionix_adsb_transceiver_health_report_encode(vehicle_system_id,
250  MAV_COMP_ID_ADSB,
251  &msg, &health_report);
252  chan0_status->current_tx_seq = saved_seq;
253  chan0_status->flags = saved_flags;
254 
255  uint8_t msgbuf[len];
256  len = mavlink_msg_to_send_buffer(msgbuf, &msg);
257  if (len > 0) {
258  mav_socket.send(msgbuf, len);
259  ::printf("ADSBsim send tx health packet\n");
260  }
261  }
262 
263 }
264 
265 } // namespace SITL
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
int printf(const char *fmt,...)
Definition: stdio.c:113
AP_Int8 adsb_tx
Definition: SITL.h:171
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
uint32_t last_tx_report_ms
Definition: SIM_ADSB.h:61
AP_Int16 adsb_plane_count
Definition: SITL.h:168
AP_Float adsb_altitude_m
Definition: SITL.h:170
const float reporting_period_ms
Definition: SIM_ADSB.h:58
ADSB_Vehicle vehicles[num_vehicles_MAX]
Definition: SIM_ADSB.h:55
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
Definition: AP_Math.cpp:140
const uint16_t target_port
Definition: SIM_ADSB.h:50
mavlink_status_t status
Definition: SIM_ADSB.h:73
AP_Float adsb_radius_m
Definition: SITL.h:169
struct SITL::ADSB::@198 mavlink
uint32_t last_update_us
Definition: SIM_ADSB.h:60
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
char callsign[9]
Definition: SIM_ADSB.h:38
void send_report(void)
Definition: SIM_ADSB.cpp:108
void update(void)
Definition: SIM_ADSB.cpp:73
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
Location home
Definition: SIM_ADSB.h:52
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
union UU msgbuf
static double rand_normal(double mean, double stddev)
SocketAPM mav_socket
Definition: SIM_ADSB.h:68
SITL * _sitl
Definition: SIM_ADSB.cpp:28
static const uint8_t num_vehicles_MAX
Definition: SIM_ADSB.h:54
#define f(i)
uint32_t last_heartbeat_ms
Definition: SIM_ADSB.h:63
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
T z
Definition: vector3.h:67
static bool parse_home(const char *home_str, Location &loc, float &yaw_degrees)
const char * target_address
Definition: SIM_ADSB.h:49
static DummyVehicle vehicle
Definition: AHRS_Test.cpp:35
bool seen_heartbeat
Definition: SIM_ADSB.h:64
Vector3f position
Definition: SIM_ADSB.h:36
uint8_t num_vehicles
Definition: SIM_ADSB.h:53
uint32_t last_report_us
Definition: SIM_ADSB.h:59
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
Vector3f velocity_ef
Definition: SIM_ADSB.h:37
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
void update(float delta_t)
Definition: SIM_ADSB.cpp:40
uint8_t vehicle_system_id
Definition: SIM_ADSB.h:65
#define degrees(x)
Definition: moduletest.c:23
uint8_t vehicle_component_id
Definition: SIM_ADSB.h:66
uint32_t ICAO_address
Definition: SIM_ADSB.h:39
uint32_t micros()
Definition: system.cpp:152
ADSB(const struct sitl_fdm &_fdm, const char *home_str)
Definition: SIM_ADSB.cpp:30
T x
Definition: vector3.h:67