SIM_AirSim.h 3.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. Simulator connector for Airsim: https://github.com/Microsoft/AirSim
  15. */
  16. #pragma once
  17. #include <AP_HAL/utility/Socket.h>
  18. #include "SIM_Aircraft.h"
  19. namespace SITL {
  20. /*
  21. Airsim Simulator
  22. */
  23. class AirSim : public Aircraft {
  24. public:
  25. AirSim(const char *frame_str);
  26. /* update model by one time step */
  27. void update(const struct sitl_input &input) override;
  28. /* static object creator */
  29. static Aircraft *create(const char *frame_str) {
  30. return new AirSim(frame_str);
  31. }
  32. /* Create and set in/out socket for Airsim simulator */
  33. void set_interface_ports(const char* address, const int port_in, const int port_out) override;
  34. private:
  35. /*
  36. rotor control packet sent by Ardupilot
  37. */
  38. static const int kArduCopterRotorControlCount = 11;
  39. struct servo_packet {
  40. uint16_t pwm[kArduCopterRotorControlCount];
  41. };
  42. // default connection_info_.ip_address
  43. const char *airsim_ip = "127.0.0.1";
  44. // connection_info_.ip_port
  45. uint16_t airsim_sensor_port = 9003;
  46. // connection_info_.sitl_ip_port
  47. uint16_t airsim_control_port = 9002;
  48. SocketAPM sock;
  49. double average_frame_time;
  50. uint64_t frame_counter;
  51. uint64_t last_frame_count;
  52. uint64_t last_timestamp;
  53. void send_servos(const struct sitl_input &input);
  54. void recv_fdm();
  55. void report_FPS(void);
  56. bool parse_sensors(const char *json);
  57. // buffer for parsing pose data in JSON format
  58. uint8_t sensor_buffer[65000];
  59. uint32_t sensor_buffer_len;
  60. enum data_type {
  61. DATA_UINT64,
  62. DATA_FLOAT,
  63. DATA_DOUBLE,
  64. DATA_VECTOR3F,
  65. DATA_VECTOR3F_ARRAY,
  66. DATA_FLOAT_ARRAY,
  67. };
  68. struct {
  69. uint64_t timestamp;
  70. struct {
  71. Vector3f angular_velocity;
  72. Vector3f linear_acceleration;
  73. } imu;
  74. struct {
  75. float lat, lon, alt;
  76. } gps;
  77. struct {
  78. float roll, pitch, yaw;
  79. } pose;
  80. struct {
  81. Vector3f world_linear_velocity;
  82. } velocity;
  83. struct {
  84. struct vector3f_array points;
  85. } lidar;
  86. struct {
  87. struct float_array rc_channels;
  88. } rc;
  89. } state;
  90. // table to aid parsing of JSON sensor data
  91. struct keytable {
  92. const char *section;
  93. const char *key;
  94. void *ptr;
  95. enum data_type type;
  96. } keytable[12] = {
  97. { "", "timestamp", &state.timestamp, DATA_UINT64 },
  98. { "imu", "angular_velocity", &state.imu.angular_velocity, DATA_VECTOR3F },
  99. { "imu", "linear_acceleration", &state.imu.linear_acceleration, DATA_VECTOR3F },
  100. { "gps", "lat", &state.gps.lat, DATA_FLOAT },
  101. { "gps", "lon", &state.gps.lon, DATA_FLOAT },
  102. { "gps", "alt", &state.gps.alt, DATA_FLOAT },
  103. { "pose", "roll", &state.pose.roll, DATA_FLOAT },
  104. { "pose", "pitch", &state.pose.pitch, DATA_FLOAT },
  105. { "pose", "yaw", &state.pose.yaw, DATA_FLOAT },
  106. { "velocity", "world_linear_velocity", &state.velocity.world_linear_velocity, DATA_VECTOR3F },
  107. { "lidar", "point_cloud", &state.lidar.points, DATA_VECTOR3F_ARRAY },
  108. { "rc", "channels", &state.rc.rc_channels, DATA_FLOAT_ARRAY },
  109. };
  110. };
  111. }