SITL_State.h 6.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  4. #include "AP_HAL_SITL.h"
  5. #include "AP_HAL_SITL_Namespace.h"
  6. #include "HAL_SITL_Class.h"
  7. #include "RCInput.h"
  8. #include <sys/types.h>
  9. #include <sys/socket.h>
  10. #include <netinet/in.h>
  11. #include <netinet/udp.h>
  12. #include <arpa/inet.h>
  13. #include <AP_Baro/AP_Baro.h>
  14. #include <AP_InertialSensor/AP_InertialSensor.h>
  15. #include <AP_Compass/AP_Compass.h>
  16. #include <AP_Terrain/AP_Terrain.h>
  17. #include <SITL/SITL.h>
  18. #include <SITL/SITL_Input.h>
  19. #include <SITL/SIM_Gimbal.h>
  20. #include <SITL/SIM_ADSB.h>
  21. #include <SITL/SIM_Vicon.h>
  22. #include <AP_HAL/utility/Socket.h>
  23. class HAL_SITL;
  24. class HALSITL::SITL_State {
  25. friend class HALSITL::Scheduler;
  26. friend class HALSITL::Util;
  27. friend class HALSITL::GPIO;
  28. public:
  29. void init(int argc, char * const argv[]);
  30. enum vehicle_type {
  31. ArduCopter,
  32. APMrover2,
  33. ArduPlane,
  34. ArduSub
  35. };
  36. int gps_pipe(void);
  37. int gps2_pipe(void);
  38. ssize_t gps_read(int fd, void *buf, size_t count);
  39. uint16_t pwm_output[SITL_NUM_CHANNELS];
  40. uint16_t pwm_input[SITL_RC_INPUT_CHANNELS];
  41. bool output_ready = false;
  42. bool new_rc_input;
  43. void loop_hook(void);
  44. uint16_t base_port(void) const {
  45. return _base_port;
  46. }
  47. // create a file desciptor attached to a virtual device; type of
  48. // device is given by name parameter
  49. int sim_fd(const char *name, const char *arg);
  50. bool use_rtscts(void) const {
  51. return _use_rtscts;
  52. }
  53. // simulated airspeed, sonar and battery monitor
  54. uint16_t sonar_pin_value; // pin 0
  55. uint16_t airspeed_pin_value; // pin 1
  56. uint16_t airspeed_2_pin_value; // pin 2
  57. uint16_t voltage_pin_value; // pin 13
  58. uint16_t current_pin_value; // pin 12
  59. uint16_t voltage2_pin_value; // pin 15
  60. uint16_t current2_pin_value; // pin 14
  61. // paths for UART devices
  62. const char *_uart_path[7] {
  63. "tcp:0:wait",
  64. "GPS1",
  65. "tcp:2",
  66. "tcp:3",
  67. "GPS2",
  68. "tcp:5",
  69. "tcp:6",
  70. };
  71. /* parse a home location string */
  72. static bool parse_home(const char *home_str,
  73. Location &loc,
  74. float &yaw_degrees);
  75. private:
  76. void _parse_command_line(int argc, char * const argv[]);
  77. void _set_param_default(const char *parm);
  78. void _usage(void);
  79. void _sitl_setup(const char *home_str);
  80. void _setup_fdm(void);
  81. void _setup_timer(void);
  82. void _setup_adc(void);
  83. void set_height_agl(void);
  84. void _update_rangefinder(float range_value);
  85. void _set_signal_handlers(void) const;
  86. struct gps_data {
  87. double latitude;
  88. double longitude;
  89. float altitude;
  90. double speedN;
  91. double speedE;
  92. double speedD;
  93. double yaw;
  94. bool have_lock;
  95. };
  96. #define MAX_GPS_DELAY 100
  97. gps_data _gps_data[MAX_GPS_DELAY];
  98. bool _gps_has_basestation_position;
  99. gps_data _gps_basestation_data;
  100. void _gps_write(const uint8_t *p, uint16_t size, uint8_t instance);
  101. void _gps_send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size, uint8_t instance);
  102. void _update_gps_ubx(const struct gps_data *d, uint8_t instance);
  103. void _update_gps_mtk(const struct gps_data *d, uint8_t instance);
  104. void _update_gps_mtk16(const struct gps_data *d, uint8_t instance);
  105. void _update_gps_mtk19(const struct gps_data *d, uint8_t instance);
  106. uint16_t _gps_nmea_checksum(const char *s);
  107. void _gps_nmea_printf(uint8_t instance, const char *fmt, ...);
  108. void _update_gps_nmea(const struct gps_data *d, uint8_t instance);
  109. void _sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload, uint8_t instance);
  110. void _update_gps_sbp(const struct gps_data *d, uint8_t instance);
  111. void _update_gps_sbp2(const struct gps_data *d, uint8_t instance);
  112. void _update_gps_file(uint8_t instance);
  113. void _update_gps_nova(const struct gps_data *d, uint8_t instance);
  114. void _nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen, uint8_t instance);
  115. uint32_t CRC32Value(uint32_t icrc);
  116. uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc);
  117. void _update_gps(double latitude, double longitude, float altitude,
  118. double speedN, double speedE, double speedD,
  119. double yaw, bool have_lock);
  120. void _update_airspeed(float airspeed);
  121. void _update_gps_instance(SITL::SITL::GPSType gps_type, const struct gps_data *d, uint8_t instance);
  122. void _check_rc_input(void);
  123. bool _read_rc_sitl_input();
  124. void _fdm_input_local(void);
  125. void _output_to_flightgear(void);
  126. void _simulator_servos(struct sitl_input &input);
  127. void _simulator_output(bool synthetic_clock_mode);
  128. uint16_t _airspeed_sensor(float airspeed);
  129. uint16_t _ground_sonar();
  130. void _fdm_input_step(void);
  131. void wait_clock(uint64_t wait_time_usec);
  132. // internal state
  133. enum vehicle_type _vehicle;
  134. uint16_t _framerate;
  135. uint8_t _instance;
  136. uint16_t _base_port;
  137. pid_t _parent_pid;
  138. uint32_t _update_count;
  139. AP_Baro *_barometer;
  140. AP_InertialSensor *_ins;
  141. Scheduler *_scheduler;
  142. Compass *_compass;
  143. #if AP_TERRAIN_AVAILABLE
  144. AP_Terrain *_terrain;
  145. #endif
  146. SocketAPM _sitl_rc_in{true};
  147. SITL::SITL *_sitl;
  148. uint16_t _rcin_port;
  149. uint16_t _fg_view_port;
  150. uint16_t _irlock_port;
  151. float _current;
  152. bool _synthetic_clock_mode;
  153. bool _use_rtscts;
  154. bool _use_fg_view;
  155. const char *_fg_address;
  156. // delay buffer variables
  157. static const uint8_t mag_buffer_length = 250;
  158. static const uint8_t wind_buffer_length = 50;
  159. // magnetometer delay buffer variables
  160. struct readings_mag {
  161. uint32_t time;
  162. Vector3f data;
  163. };
  164. uint8_t store_index_mag;
  165. uint32_t last_store_time_mag;
  166. VectorN<readings_mag,mag_buffer_length> buffer_mag;
  167. uint32_t time_delta_mag;
  168. uint32_t delayed_time_mag;
  169. // airspeed sensor delay buffer variables
  170. struct readings_wind {
  171. uint32_t time;
  172. float data;
  173. };
  174. uint8_t store_index_wind;
  175. uint32_t last_store_time_wind;
  176. VectorN<readings_wind,wind_buffer_length> buffer_wind;
  177. VectorN<readings_wind,wind_buffer_length> buffer_wind_2;
  178. uint32_t time_delta_wind;
  179. uint32_t delayed_time_wind;
  180. uint32_t wind_start_delay_micros;
  181. // internal SITL model
  182. SITL::Aircraft *sitl_model;
  183. // simulated gimbal
  184. bool enable_gimbal;
  185. SITL::Gimbal *gimbal;
  186. // simulated ADSb
  187. SITL::ADSB *adsb;
  188. // simulated vicon system:
  189. SITL::Vicon *vicon;
  190. // output socket for flightgear viewing
  191. SocketAPM fg_socket{true};
  192. const char *defaults_path = HAL_PARAM_DEFAULTS_PATH;
  193. const char *_home_str;
  194. };
  195. #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL