APM:Libraries
SITL_State.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 
5 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
6 
7 #include "AP_HAL_SITL.h"
9 #include "HAL_SITL_Class.h"
10 #include "RCInput.h"
11 
12 #include <sys/types.h>
13 #include <sys/socket.h>
14 #include <netinet/in.h>
15 #include <netinet/udp.h>
16 #include <arpa/inet.h>
17 
18 #include <AP_Baro/AP_Baro.h>
20 #include <AP_Compass/AP_Compass.h>
21 #include <AP_Terrain/AP_Terrain.h>
22 #include <SITL/SITL.h>
23 #include <SITL/SIM_Gimbal.h>
24 #include <SITL/SIM_ADSB.h>
25 #include <SITL/SIM_Vicon.h>
26 #include <AP_HAL/utility/Socket.h>
27 
28 class HAL_SITL;
29 
31  friend class HALSITL::Scheduler;
32  friend class HALSITL::Util;
33  friend class HALSITL::GPIO;
34 public:
35  void init(int argc, char * const argv[]);
36 
37  enum vehicle_type {
42  };
43 
44  int gps_pipe(void);
45  int gps2_pipe(void);
46  ssize_t gps_read(int fd, void *buf, size_t count);
49  bool output_ready = false;
51  void loop_hook(void);
52  uint16_t base_port(void) const {
53  return _base_port;
54  }
55 
56  // create a file desciptor attached to a virtual device; type of
57  // device is given by name parameter
58  int sim_fd(const char *name, const char *arg);
59 
60  bool use_rtscts(void) const {
61  return _use_rtscts;
62  }
63 
64  // simulated airspeed, sonar and battery monitor
65  uint16_t sonar_pin_value; // pin 0
66  uint16_t airspeed_pin_value; // pin 1
67  uint16_t airspeed_2_pin_value; // pin 2
68  uint16_t voltage_pin_value; // pin 13
69  uint16_t current_pin_value; // pin 12
70  uint16_t voltage2_pin_value; // pin 15
71  uint16_t current2_pin_value; // pin 14
72 
73  // return TCP client address for uartC
74  const char *get_client_address(void) const { return _client_address; }
75 
76  // paths for UART devices
77  const char *_uart_path[6] {
78  "tcp:0:wait",
79  "GPS1",
80  "tcp:2",
81  "tcp:3",
82  "GPS2",
83  "tcp:5",
84  };
85 
86 private:
87  void _parse_command_line(int argc, char * const argv[]);
88  void _set_param_default(const char *parm);
89  void _usage(void);
90  void _sitl_setup(const char *home_str);
91  void _setup_fdm(void);
92  void _setup_timer(void);
93  void _setup_adc(void);
94 
95  void set_height_agl(void);
96  void _update_rangefinder(float range_value);
97  void _set_signal_handlers(void) const;
98 
99  struct gps_data {
100  double latitude;
101  double longitude;
102  float altitude;
103  double speedN;
104  double speedE;
105  double speedD;
106  bool have_lock;
107  };
108 
109 #define MAX_GPS_DELAY 100
111 
114  void _gps_write(const uint8_t *p, uint16_t size, uint8_t instance);
115  void _gps_send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size, uint8_t instance);
116  void _update_gps_ubx(const struct gps_data *d, uint8_t instance);
117  void _update_gps_mtk(const struct gps_data *d, uint8_t instance);
118  void _update_gps_mtk16(const struct gps_data *d, uint8_t instance);
119  void _update_gps_mtk19(const struct gps_data *d, uint8_t instance);
120  uint16_t _gps_nmea_checksum(const char *s);
121  void _gps_nmea_printf(uint8_t instance, const char *fmt, ...);
122  void _update_gps_nmea(const struct gps_data *d, uint8_t instance);
123  void _sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload, uint8_t instance);
124  void _update_gps_sbp(const struct gps_data *d, uint8_t instance);
125  void _update_gps_sbp2(const struct gps_data *d, uint8_t instance);
126  void _update_gps_file(uint8_t instance);
127  void _update_gps_nova(const struct gps_data *d, uint8_t instance);
128  void _nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen, uint8_t instance);
129  uint32_t CRC32Value(uint32_t icrc);
130  uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc);
131 
132  void _update_gps(double latitude, double longitude, float altitude,
133  double speedN, double speedE, double speedD, bool have_lock);
134  void _update_airspeed(float airspeed);
135  void _update_gps_instance(SITL::SITL::GPSType gps_type, const struct gps_data *d, uint8_t instance);
136  void _check_rc_input(void);
137  void _fdm_input_local(void);
138  void _output_to_flightgear(void);
140  void _simulator_output(bool synthetic_clock_mode);
141  uint16_t _airspeed_sensor(float airspeed);
142  uint16_t _ground_sonar();
143  void _fdm_input_step(void);
144 
145  void wait_clock(uint64_t wait_time_usec);
146 
147  // internal state
149  uint16_t _framerate;
150  uint8_t _instance;
151  uint16_t _base_port;
152  struct sockaddr_in _rcout_addr;
153  pid_t _parent_pid;
154  uint32_t _update_count;
155 
160 #if AP_TERRAIN_AVAILABLE
161  AP_Terrain *_terrain;
162 #endif
163 
164  SocketAPM _sitl_rc_in{true};
166  uint16_t _rcout_port;
167  uint16_t _rcin_port;
168  uint16_t _fg_view_port;
169  uint16_t _irlock_port;
170  float _current;
171 
173 
176 
177  const char *_fdm_address;
178 
179  // delay buffer variables
180  static const uint8_t mag_buffer_length = 250;
181  static const uint8_t wind_buffer_length = 50;
182 
183  // magnetometer delay buffer variables
184  struct readings_mag {
185  uint32_t time;
187  };
191  uint32_t time_delta_mag;
193 
194  // airspeed sensor delay buffer variables
195  struct readings_wind {
196  uint32_t time;
197  float data;
198  };
203  uint32_t time_delta_wind;
206 
207  // internal SITL model
209 
210  // simulated gimbal
213 
214  // simulated ADSb
216 
217  // simulated vicon system:
219 
220  // output socket for flightgear viewing
221  SocketAPM fg_socket{true};
222 
223  // TCP address to connect uartC to
224  const char *_client_address;
225 
227 
228  const char *_home_str;
229 };
230 
231 #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
SocketAPM fg_socket
Definition: SITL_State.h:221
void loop_hook(void)
uint16_t _fg_view_port
Definition: SITL_State.h:168
ssize_t gps_read(int fd, void *buf, size_t count)
Definition: sitl_gps.cpp:49
uint16_t _gps_nmea_checksum(const char *s)
Definition: sitl_gps.cpp:609
uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc)
Definition: sitl_gps.cpp:1114
uint32_t _update_count
Definition: SITL_State.h:154
uint32_t delayed_time_wind
Definition: SITL_State.h:204
#define SITL_NUM_CHANNELS
Definition: SITL.h:35
gps_data _gps_basestation_data
Definition: SITL_State.h:113
uint16_t voltage2_pin_value
Definition: SITL_State.h:70
const char * _client_address
Definition: SITL_State.h:224
void _setup_fdm(void)
Definition: SITL_State.cpp:117
uint32_t wind_start_delay_micros
Definition: SITL_State.h:205
void _update_gps_file(uint8_t instance)
Definition: sitl_gps.cpp:1126
VectorN< readings_mag, mag_buffer_length > buffer_mag
Definition: SITL_State.h:190
int gps_pipe(void)
Definition: sitl_gps.cpp:68
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
void _parse_command_line(int argc, char *const argv[])
void _set_param_default(const char *parm)
Definition: SITL_State.cpp:26
bool _gps_has_basestation_position
Definition: SITL_State.h:112
const char * _uart_path[6]
Definition: SITL_State.h:77
void _output_to_flightgear(void)
Definition: SITL_State.cpp:242
void _update_airspeed(float airspeed)
void _update_gps_nmea(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:644
SITL::Gimbal * gimbal
Definition: SITL_State.h:212
void _update_gps_nova(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:954
void _gps_send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size, uint8_t instance)
Definition: sitl_gps.cpp:149
uint16_t current2_pin_value
Definition: SITL_State.h:71
AP_InertialSensor * _ins
Definition: SITL_State.h:157
void _update_gps_mtk16(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:493
void _fdm_input_step(void)
Definition: SITL_State.cpp:133
uint16_t airspeed_2_pin_value
Definition: SITL_State.h:67
const char * _home_str
Definition: SITL_State.h:228
void _update_gps_sbp(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:723
const char * name
Definition: BusTest.cpp:11
uint8_t store_index_mag
Definition: SITL_State.h:188
Compass * _compass
Definition: SITL_State.h:159
#define HAL_PARAM_DEFAULTS_PATH
int gps2_pipe(void)
Definition: sitl_gps.cpp:86
void set_height_agl(void)
Definition: SITL_State.cpp:505
uint32_t time_delta_mag
Definition: SITL_State.h:191
uint16_t _rcout_port
Definition: SITL_State.h:166
gps_data _gps_data[MAX_GPS_DELAY]
Definition: SITL_State.h:110
uint32_t last_store_time_mag
Definition: SITL_State.h:189
uint16_t voltage_pin_value
Definition: SITL_State.h:68
void _gps_nmea_printf(uint8_t instance, const char *fmt,...)
Definition: sitl_gps.cpp:622
uint16_t _airspeed_sensor(float airspeed)
uint8_t store_index_wind
Definition: SITL_State.h:199
uint16_t pwm_input[SITL_RC_INPUT_CHANNELS]
Definition: SITL_State.h:48
void _simulator_output(bool synthetic_clock_mode)
void _fdm_input_local(void)
Definition: SITL_State.cpp:277
uint32_t delayed_time_mag
Definition: SITL_State.h:192
uint16_t current_pin_value
Definition: SITL_State.h:69
AP_Baro * _barometer
Definition: SITL_State.h:156
void _update_gps_ubx(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:191
SocketAPM _sitl_rc_in
Definition: SITL_State.h:164
static const uint8_t mag_buffer_length
Definition: SITL_State.h:180
const char * fmt
Definition: Printf.cpp:14
void _update_gps(double latitude, double longitude, float altitude, double speedN, double speedE, double speedD, bool have_lock)
Definition: sitl_gps.cpp:1161
void _set_signal_handlers(void) const
void _sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload, uint8_t instance)
Definition: sitl_gps.cpp:700
VectorN< readings_wind, wind_buffer_length > buffer_wind
Definition: SITL_State.h:201
SITL::Aircraft * sitl_model
Definition: SITL_State.h:208
void _check_rc_input(void)
Definition: SITL_State.cpp:211
GPSType
Definition: SITL.h:58
uint16_t pwm_output[SITL_NUM_CHANNELS]
Definition: SITL_State.h:47
uint16_t sonar_pin_value
Definition: SITL_State.h:65
#define SITL_RC_INPUT_CHANNELS
Definition: RCInput.h:6
void _update_rangefinder(float range_value)
const char * _fdm_address
Definition: SITL_State.h:177
void init(int argc, char *const argv[])
Definition: SITL_State.cpp:492
uint32_t last_store_time_wind
Definition: SITL_State.h:200
void _update_gps_mtk(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:436
void _gps_write(const uint8_t *p, uint16_t size, uint8_t instance)
Definition: sitl_gps.cpp:104
struct sockaddr_in _rcout_addr
Definition: SITL_State.h:152
bool use_rtscts(void) const
Definition: SITL_State.h:60
void _update_gps_mtk19(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:551
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
uint32_t CRC32Value(uint32_t icrc)
Definition: sitl_gps.cpp:1100
void _setup_timer(void)
void _nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen, uint8_t instance)
Definition: sitl_gps.cpp:1088
Scheduler * _scheduler
Definition: SITL_State.h:158
#define MAX_GPS_DELAY
Definition: SITL_State.h:109
void _sitl_setup(const char *home_str)
Definition: SITL_State.cpp:62
SITL::SITL * _sitl
Definition: SITL_State.h:165
void _simulator_servos(SITL::Aircraft::sitl_input &input)
Definition: SITL_State.cpp:337
uint16_t airspeed_pin_value
Definition: SITL_State.h:66
void _update_gps_sbp2(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:839
const char * get_client_address(void) const
Definition: SITL_State.h:74
enum vehicle_type _vehicle
Definition: SITL_State.h:148
SITL::Vicon * vicon
Definition: SITL_State.h:218
int sim_fd(const char *name, const char *arg)
Definition: SITL_State.cpp:195
void _setup_adc(void)
const char * defaults_path
Definition: SITL_State.h:226
uint32_t time_delta_wind
Definition: SITL_State.h:203
void _update_gps_instance(SITL::SITL::GPSType gps_type, const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:1294
void wait_clock(uint64_t wait_time_usec)
Definition: SITL_State.cpp:187
static const uint8_t wind_buffer_length
Definition: SITL_State.h:181
SITL::ADSB * adsb
Definition: SITL_State.h:215
uint16_t _ground_sonar()
uint16_t _irlock_port
Definition: SITL_State.h:169
VectorN< readings_wind, wind_buffer_length > buffer_wind_2
Definition: SITL_State.h:202
uint16_t base_port(void) const
Definition: SITL_State.h:52