APM:Libraries
SITL_State.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
4 
5 #include "AP_HAL_SITL.h"
7 #include "HAL_SITL_Class.h"
8 #include "UARTDriver.h"
9 #include "Scheduler.h"
10 
11 #include <stdio.h>
12 #include <signal.h>
13 #include <unistd.h>
14 #include <stdlib.h>
15 #include <errno.h>
16 #include <sys/select.h>
17 
18 #include <AP_Param/AP_Param.h>
19 #include <SITL/SIM_JSBSim.h>
20 #include <AP_HAL/utility/Socket.h>
21 
22 extern const AP_HAL::HAL& hal;
23 
24 using namespace HALSITL;
25 
26 void SITL_State::_set_param_default(const char *parm)
27 {
28  char *pdup = strdup(parm);
29  char *p = strchr(pdup, '=');
30  if (p == nullptr) {
31  printf("Please specify parameter as NAME=VALUE");
32  exit(1);
33  }
34  float value = strtof(p+1, nullptr);
35  *p = 0;
36  enum ap_var_type var_type;
37  AP_Param *vp = AP_Param::find(pdup, &var_type);
38  if (vp == nullptr) {
39  printf("Unknown parameter %s\n", pdup);
40  exit(1);
41  }
42  if (var_type == AP_PARAM_FLOAT) {
43  ((AP_Float *)vp)->set_and_save(value);
44  } else if (var_type == AP_PARAM_INT32) {
45  ((AP_Int32 *)vp)->set_and_save(value);
46  } else if (var_type == AP_PARAM_INT16) {
47  ((AP_Int16 *)vp)->set_and_save(value);
48  } else if (var_type == AP_PARAM_INT8) {
49  ((AP_Int8 *)vp)->set_and_save(value);
50  } else {
51  printf("Unable to set parameter %s\n", pdup);
52  exit(1);
53  }
54  printf("Set parameter %s to %f\n", pdup, value);
55  free(pdup);
56 }
57 
58 
59 /*
60  setup for SITL handling
61  */
62 void SITL_State::_sitl_setup(const char *home_str)
63 {
64  _home_str = home_str;
65 
66 #if !defined(__CYGWIN__) && !defined(__CYGWIN64__)
67  _parent_pid = getppid();
68 #endif
69  _rcout_addr.sin_family = AF_INET;
70  _rcout_addr.sin_port = htons(_rcout_port);
71  inet_pton(AF_INET, _fdm_address, &_rcout_addr.sin_addr);
72 
73 #ifndef HIL_MODE
74  _setup_fdm();
75 #endif
76  fprintf(stdout, "Starting SITL input\n");
77 
78  // find the barometer object if it exists
82  _compass = (Compass *)AP_Param::find_object("COMPASS_");
83 #if AP_TERRAIN_AVAILABLE
84  _terrain = (AP_Terrain *)AP_Param::find_object("TERRAIN_");
85 #endif
86 
87  if (_sitl != nullptr) {
88  // setup some initial values
89 #ifndef HIL_MODE
91  _update_gps(0, 0, 0, 0, 0, 0, false);
93 #endif
94  if (enable_gimbal) {
96  }
97 
98  if (_use_fg_view) {
99  fg_socket.connect("127.0.0.1", _fg_view_port);
100  }
101 
102  fprintf(stdout, "Using Irlock at port : %d\n", _irlock_port);
104  }
105 
106  if (_synthetic_clock_mode) {
107  // start with non-zero clock
108  hal.scheduler->stop_clock(1);
109  }
110 }
111 
112 
113 #ifndef HIL_MODE
114 /*
115  setup a SITL FDM listening UDP port
116  */
118 {
119  if (!_sitl_rc_in.bind("0.0.0.0", _rcin_port)) {
120  fprintf(stderr, "SITL: socket bind failed on RC in port : %d - %s\n", _rcin_port, strerror(errno));
121  fprintf(stderr, "Abording launch...\n");
122  exit(1);
123  }
124  _sitl_rc_in.reuseaddress();
125  _sitl_rc_in.set_blocking(false);
126 }
127 #endif
128 
129 
130 /*
131  step the FDM by one time step
132  */
134 {
135  static uint32_t last_pwm_input = 0;
136 
138 
139  /* make sure we die if our parent dies */
140  if (kill(_parent_pid, 0) != 0) {
141  exit(1);
142  }
143 
144  if (_scheduler->interrupts_are_blocked() || _sitl == nullptr) {
145  return;
146  }
147 
148  // simulate RC input at 50Hz
149  if (AP_HAL::millis() - last_pwm_input >= 20 && _sitl->rc_fail == 0) {
150  last_pwm_input = AP_HAL::millis();
151  new_rc_input = true;
152  }
153 
155 
156  if (_update_count == 0 && _sitl != nullptr) {
157  _update_gps(0, 0, 0, 0, 0, 0, false);
160  return;
161  }
162 
163  if (_sitl != nullptr) {
167  !_sitl->gps_disable);
170 
171  if (_sitl->adsb_plane_count >= 0 &&
172  adsb == nullptr) {
174  } else if (_sitl->adsb_plane_count == -1 &&
175  adsb != nullptr) {
176  delete adsb;
177  adsb = nullptr;
178  }
179  }
180 
181  // trigger all APM timers.
184 }
185 
186 
187 void SITL_State::wait_clock(uint64_t wait_time_usec)
188 {
189  while (AP_HAL::micros64() < wait_time_usec) {
190  _fdm_input_step();
191  }
192 }
193 
194 #define streq(a, b) (!strcmp(a, b))
195 int SITL_State::sim_fd(const char *name, const char *arg)
196 {
197  if (streq(name, "vicon")) {
198  if (vicon != nullptr) {
199  AP_HAL::panic("Only one vicon system at a time");
200  }
201  vicon = new SITL::Vicon();
202  return vicon->fd();
203  }
204  AP_HAL::panic("unknown simulated device: %s", name);
205 }
206 
207 #ifndef HIL_MODE
208 /*
209  check for a SITL RC input packet
210  */
212 {
213  ssize_t size;
214  struct pwm_packet {
215  uint16_t pwm[16];
216  } pwm_pkt;
217 
218  size = _sitl_rc_in.recv(&pwm_pkt, sizeof(pwm_pkt), 0);
219  switch (size) {
220  case 8*2:
221  case 16*2: {
222  // a packet giving the receiver PWM inputs
223  uint8_t i;
224  for (i=0; i<size/2; i++) {
225  // setup the pwm input for the RC channel inputs
226  if (i < _sitl->state.rcin_chan_count) {
227  // we're using rc from simulator
228  continue;
229  }
230  if (pwm_pkt.pwm[i] != 0) {
231  pwm_input[i] = pwm_pkt.pwm[i];
232  }
233  }
234  break;
235  }
236  }
237 }
238 
239 /*
240  output current state to flightgear
241  */
243 {
244  SITL::FGNetFDM fdm {};
245  const SITL::sitl_fdm &sfdm = _sitl->state;
246 
247  fdm.version = 0x18;
248  fdm.padding = 0;
249  fdm.longitude = radians(sfdm.longitude);
250  fdm.latitude = radians(sfdm.latitude);
251  fdm.altitude = sfdm.altitude;
252  fdm.agl = sfdm.altitude;
253  fdm.phi = radians(sfdm.rollDeg);
254  fdm.theta = radians(sfdm.pitchDeg);
255  fdm.psi = radians(sfdm.yawDeg);
256  if (_vehicle == ArduCopter) {
257  fdm.num_engines = 4;
258  for (uint8_t i=0; i<4; i++) {
259  fdm.rpm[i] = constrain_float((pwm_output[i]-1000), 0, 1000);
260  }
261  } else {
262  fdm.num_engines = 4;
263  fdm.rpm[0] = constrain_float((pwm_output[2]-1000)*3, 0, 3000);
264  // for quadplane
265  fdm.rpm[1] = constrain_float((pwm_output[5]-1000)*12, 0, 12000);
266  fdm.rpm[2] = constrain_float((pwm_output[6]-1000)*12, 0, 12000);
267  fdm.rpm[3] = constrain_float((pwm_output[7]-1000)*12, 0, 12000);
268  }
269  fdm.ByteSwap();
270 
271  fg_socket.send(&fdm, sizeof(fdm));
272 }
273 
274 /*
275  get FDM input from a local model
276  */
278 {
280 
281  // check for direct RC input
282  _check_rc_input();
283 
284  // construct servos structure for FDM
285  _simulator_servos(input);
286 
287  // update the model
288  sitl_model->update(input);
289 
290  // get FDM output from the model
291  if (_sitl) {
294 
295  if (_sitl->rc_fail == 0) {
296  for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) {
297  pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000;
298  }
299  }
300  }
301 
302  if (gimbal != nullptr) {
303  gimbal->update();
304  }
305  if (adsb != nullptr) {
306  adsb->update();
307  }
308  if (vicon != nullptr) {
309  Quaternion attitude;
310  sitl_model->get_attitude(attitude);
313  attitude);
314  }
315 
316  if (_sitl && _use_fg_view) {
318  }
319 
320  // update simulation time
321  if (_sitl) {
323  } else {
325  }
326 
327  set_height_agl();
328 
329  _synthetic_clock_mode = true;
330  _update_count++;
331 }
332 #endif
333 
334 /*
335  create sitl_input structure for sending to FDM
336  */
338 {
339  static uint32_t last_update_usec;
340 
341  /* this maps the registers used for PWM outputs. The RC
342  * driver updates these whenever it wants the channel output
343  * to change */
344  uint8_t i;
345 
346  if (last_update_usec == 0 || !output_ready) {
347  for (i=0; i<SITL_NUM_CHANNELS; i++) {
348  pwm_output[i] = 1000;
349  }
350  if (_vehicle == ArduPlane) {
351  pwm_output[0] = pwm_output[1] = pwm_output[3] = 1500;
352  }
353  if (_vehicle == APMrover2) {
354  pwm_output[0] = pwm_output[1] = pwm_output[2] = pwm_output[3] = 1500;
355  }
356  }
357 
358  // output at chosen framerate
359  uint32_t now = AP_HAL::micros();
360  last_update_usec = now;
361 
362  float altitude = _barometer?_barometer->get_altitude():0;
363  float wind_speed = 0;
364  float wind_direction = 0;
365  float wind_dir_z = 0;
366 
367  // give 5 seconds to calibrate airspeed sensor at 0 wind speed
368  if (wind_start_delay_micros == 0) {
370  } else if (_sitl && (now - wind_start_delay_micros) > 5000000 ) {
371  // The EKF does not like step inputs so this LPF keeps it happy.
372  wind_speed = _sitl->wind_speed_active = (0.95f*_sitl->wind_speed_active) + (0.05f*_sitl->wind_speed);
373  wind_direction = _sitl->wind_direction_active = (0.95f*_sitl->wind_direction_active) + (0.05f*_sitl->wind_direction);
374  wind_dir_z = _sitl->wind_dir_z_active = (0.95f*_sitl->wind_dir_z_active) + (0.05f*_sitl->wind_dir_z);
375 
376  // pass wind into simulators using different wind types via param SIM_WIND_T*.
377  switch (_sitl->wind_type) {
379  if (altitude < _sitl->wind_type_alt) {
380  wind_speed *= sqrtf(MAX(altitude / _sitl->wind_type_alt, 0));
381  }
382  break;
383 
385  wind_speed += (altitude - _sitl->wind_type_alt) * _sitl->wind_type_coef;
386  break;
387 
389  default:
390  break;
391  }
392 
393  // never allow negative wind velocity
394  wind_speed = MAX(wind_speed, 0);
395  }
396 
397  if (altitude < 0) {
398  altitude = 0;
399  }
400 
401  input.wind.speed = wind_speed;
402  input.wind.direction = wind_direction;
404  input.wind.dir_z = wind_dir_z;
405 
406  for (i=0; i<SITL_NUM_CHANNELS; i++) {
407  if (pwm_output[i] == 0xFFFF) {
408  input.servos[i] = 0;
409  } else {
410  input.servos[i] = pwm_output[i];
411  }
412  }
413 
414  float engine_mul = _sitl?_sitl->engine_mul.get():1;
415  uint8_t engine_fail = _sitl?_sitl->engine_fail.get():0;
416  bool motors_on = false;
417 
418  if (engine_fail >= ARRAY_SIZE(input.servos)) {
419  engine_fail = 0;
420  }
421  // apply engine multiplier to motor defined by the SIM_ENGINE_FAIL parameter
422  if (_vehicle != APMrover2) {
423  input.servos[engine_fail] = ((input.servos[engine_fail]-1000) * engine_mul) + 1000;
424  } else {
425  input.servos[engine_fail] = static_cast<uint16_t>(((input.servos[engine_fail] - 1500) * engine_mul) + 1500);
426  }
427 
428  if (_vehicle == ArduPlane) {
429  motors_on = ((input.servos[2] - 1000) / 1000.0f) > 0;
430  } else if (_vehicle == APMrover2) {
431  input.servos[2] = static_cast<uint16_t>(constrain_int16(input.servos[2], 1000, 2000));
432  input.servos[0] = static_cast<uint16_t>(constrain_int16(input.servos[0], 1000, 2000));
433  motors_on = ((input.servos[2] - 1500) / 500.0f) != 0;
434  } else {
435  motors_on = false;
436  // run checks on each motor
437  for (i=0; i<4; i++) {
438  // check motors do not exceed their limits
439  if (input.servos[i] > 2000) input.servos[i] = 2000;
440  if (input.servos[i] < 1000) input.servos[i] = 1000;
441  // update motor_on flag
442  if ((input.servos[i]-1000)/1000.0f > 0) {
443  motors_on = true;
444  }
445  }
446  }
447  if (_sitl) {
448  _sitl->motors_on = motors_on;
449  }
450 
451  float voltage = 0;
452  _current = 0;
453 
454  if (_sitl != nullptr) {
455  if (_sitl->state.battery_voltage <= 0) {
456  if (_vehicle == ArduSub) {
457  voltage = _sitl->batt_voltage;
458  for (i = 0; i < 6; i++) {
459  float pwm = input.servos[i];
460  //printf("i: %d, pwm: %.2f\n", i, pwm);
461  float fraction = fabsf((pwm - 1500) / 500.0f);
462 
463  voltage -= fraction * 0.5f;
464 
465  float draw = fraction * 15;
466  _current += draw;
467  }
468  } else {
469  // simulate simple battery setup
470  float throttle = motors_on?(input.servos[2]-1000) / 1000.0f:0;
471  // lose 0.7V at full throttle
472  voltage = _sitl->batt_voltage - 0.7f*fabsf(throttle);
473 
474  // assume 50A at full throttle
475  _current = 50.0f * fabsf(throttle);
476  }
477  } else {
478  // FDM provides voltage and current
479  voltage = _sitl->state.battery_voltage;
481  }
482  }
483 
484  // assume 3DR power brick
485  voltage_pin_value = ((voltage / 10.1f) / 5.0f) * 1024;
486  current_pin_value = ((_current / 17.0f) / 5.0f) * 1024;
487  // fake battery2 as just a 25% gain on the first one
488  voltage2_pin_value = ((voltage * 0.25f / 10.1f) / 5.0f) * 1024;
489  current2_pin_value = ((_current * 0.25f / 17.0f) / 5.0f) * 1024;
490 }
491 
492 void SITL_State::init(int argc, char * const argv[])
493 {
494  pwm_input[0] = pwm_input[1] = pwm_input[3] = 1500;
495  pwm_input[4] = pwm_input[7] = 1800;
496  pwm_input[2] = pwm_input[5] = pwm_input[6] = 1000;
497 
499  _parse_command_line(argc, argv);
500 }
501 
502 /*
503  set height above the ground in meters
504  */
506 {
507  static float home_alt = -1;
508 
509  if (home_alt == -1 && _sitl->state.altitude > 0) {
510  // remember home altitude as first non-zero altitude
511  home_alt = _sitl->state.altitude;
512  }
513 
514 #if AP_TERRAIN_AVAILABLE
515  if (_terrain != nullptr &&
516  _sitl != nullptr &&
518  // get height above terrain from AP_Terrain. This assumes
519  // AP_Terrain is working
520  float terrain_height_amsl;
521  struct Location location;
522  location.lat = _sitl->state.latitude*1.0e7;
523  location.lng = _sitl->state.longitude*1.0e7;
524 
525  if (_terrain->height_amsl(location, terrain_height_amsl, false)) {
526  _sitl->height_agl = _sitl->state.altitude - terrain_height_amsl;
527  return;
528  }
529  }
530 #endif
531 
532  if (_sitl != nullptr) {
533  // fall back to flat earth model
534  _sitl->height_agl = _sitl->state.altitude - home_alt;
535  }
536 }
537 
538 #endif
virtual void stop_clock(uint64_t time_usec)
Definition: Scheduler.h:66
double range
Definition: SITL.h:29
AP_Int8 wind_type
Definition: SITL.h:159
int printf(const char *fmt,...)
Definition: stdio.c:113
float rcin[8]
Definition: SITL.h:28
SocketAPM fg_socket
Definition: SITL_State.h:221
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
int fd()
Definition: SIM_Vicon.h:39
uint64_t timestamp_us
Definition: SITL.h:12
void update(void)
Definition: SIM_Gimbal.cpp:49
AP_Int16 adsb_plane_count
Definition: SITL.h:168
uint16_t _fg_view_port
Definition: SITL_State.h:168
const Vector3f & get_position() const
Definition: SIM_Aircraft.h:118
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
uint32_t _update_count
Definition: SITL_State.h:154
ap_var_type
Definition: AP_Param.h:124
double pitchDeg
Definition: SITL.h:20
uint16_t update_rate_hz
Definition: SITL.h:74
#define SITL_NUM_CHANNELS
Definition: SITL.h:35
uint16_t voltage2_pin_value
Definition: SITL_State.h:70
void _setup_fdm(void)
Definition: SITL_State.cpp:117
uint32_t wind_start_delay_micros
Definition: SITL_State.h:205
float wind_dir_z_active
Definition: SITL.h:153
uint16_t irlock_port
Definition: SITL.h:192
void update(const Location &loc, const Vector3f &position, const Quaternion &attitude)
Definition: SIM_Vicon.cpp:134
struct SITL::Aircraft::sitl_input::@201 wind
bool interrupts_are_blocked(void)
Definition: Scheduler.h:36
float height_agl
Definition: SITL.h:80
uint8_t rcin_chan_count
Definition: SITL.h:27
void _parse_command_line(int argc, char *const argv[])
void _set_param_default(const char *parm)
Definition: SITL_State.cpp:26
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
AP_Float wind_turbulance
Definition: SITL.h:156
double longitude
Definition: SITL.h:14
void sitl_begin_atomic()
Definition: Scheduler.h:40
void _output_to_flightgear(void)
Definition: SITL_State.cpp:242
void _update_airspeed(float airspeed)
double speedE
Definition: SITL.h:17
static AP_Param * find(const char *name, enum ap_var_type *ptype)
Definition: AP_Param.cpp:821
SITL::Gimbal * gimbal
Definition: SITL_State.h:212
AP_Int8 rc_fail
Definition: SITL.h:133
void update(void)
Definition: SIM_ADSB.cpp:73
bool motors_on
Definition: SITL.h:77
uint16_t current2_pin_value
Definition: SITL_State.h:71
AP_InertialSensor * _ins
Definition: SITL_State.h:157
void _fdm_input_step(void)
Definition: SITL_State.cpp:133
const char * _home_str
Definition: SITL_State.h:228
static uint16_t pwm
Definition: RCOutput.cpp:20
const char * name
Definition: BusTest.cpp:11
double airspeed
Definition: SITL.h:22
Compass * _compass
Definition: SITL_State.h:159
void set_height_agl(void)
Definition: SITL_State.cpp:505
AP_Float wind_direction
Definition: SITL.h:155
uint16_t _rcout_port
Definition: SITL_State.h:166
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
uint16_t voltage_pin_value
Definition: SITL_State.h:68
double battery_current
Definition: SITL.h:24
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
double speedD
Definition: SITL.h:17
AP_Float wind_speed
Definition: SITL.h:154
AP_Float wind_type_coef
Definition: SITL.h:161
A system for managing and storing variables that are of general interest to the system.
uint16_t pwm_input[SITL_RC_INPUT_CHANNELS]
Definition: SITL_State.h:48
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void _fdm_input_local(void)
Definition: SITL_State.cpp:277
AP_Float engine_mul
Definition: SITL.h:119
double rollDeg
Definition: SITL.h:20
uint16_t current_pin_value
Definition: SITL_State.h:69
float wind_direction_active
Definition: SITL.h:152
AP_Baro * _barometer
Definition: SITL_State.h:156
SocketAPM _sitl_rc_in
Definition: SITL_State.h:164
#define f(i)
void _update_gps(double latitude, double longitude, float altitude, double speedN, double speedE, double speedD, bool have_lock)
Definition: sitl_gps.cpp:1161
AP_Float wind_type_alt
Definition: SITL.h:160
double yawDeg
Definition: SITL.h:20
uint32_t millis()
Definition: system.cpp:157
float get_rate_hz(void) const
Definition: SIM_Aircraft.h:92
SITL::Aircraft * sitl_model
Definition: SITL_State.h:208
double speedN
Definition: SITL.h:17
static Scheduler * from(AP_HAL::Scheduler *scheduler)
Definition: Scheduler.h:14
uint64_t micros64()
Definition: system.cpp:162
AP_Float wind_dir_z
Definition: SITL.h:158
void _check_rc_input(void)
Definition: SITL_State.cpp:211
static int state
Definition: Util.cpp:20
static void timer_event()
Definition: Scheduler.h:45
uint16_t pwm_output[SITL_NUM_CHANNELS]
Definition: SITL_State.h:47
void _update_rangefinder(float range_value)
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
const char * _fdm_address
Definition: SITL_State.h:177
AP_Int8 terrain_enable
Definition: SITL.h:139
AP_Int8 engine_fail
Definition: SITL.h:120
void init(int argc, char *const argv[])
Definition: SITL_State.cpp:492
struct sockaddr_in _rcout_addr
Definition: SITL_State.h:152
void free(void *ptr)
Definition: malloc.c:81
float wind_speed_active
Definition: SITL.h:151
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
float get_altitude(void) const
Definition: AP_Baro.h:84
const Location & get_location() const
Definition: SIM_Aircraft.h:116
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
Scheduler * _scheduler
Definition: SITL_State.h:158
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void _sitl_setup(const char *home_str)
Definition: SITL_State.cpp:62
virtual void update(const struct sitl_input &input)=0
SITL::SITL * _sitl
Definition: SITL_State.h:165
void _simulator_servos(SITL::Aircraft::sitl_input &input)
Definition: SITL_State.cpp:337
void get_attitude(Quaternion &attitude) const
Definition: SIM_Aircraft.h:120
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
float voltage
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
enum vehicle_type _vehicle
Definition: SITL_State.h:148
float value
SITL::Vicon * vicon
Definition: SITL_State.h:218
int sim_fd(const char *name, const char *arg)
Definition: SITL_State.cpp:195
double latitude
Definition: SITL.h:14
AP_Int8 gps_disable
Definition: SITL.h:121
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define streq(a, b)
Definition: SITL_State.cpp:194
AP_Float batt_voltage
Definition: SITL.h:131
void fill_fdm(struct sitl_fdm &fdm)
double altitude
Definition: SITL.h:15
void wait_clock(uint64_t wait_time_usec)
Definition: SITL_State.cpp:187
uint32_t micros()
Definition: system.cpp:152
double battery_voltage
Definition: SITL.h:23
SITL::ADSB * adsb
Definition: SITL_State.h:215
struct sitl_fdm state
Definition: SITL.h:71
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint16_t _irlock_port
Definition: SITL_State.h:169