SIM_AirSim.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343
  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
  15. */
  16. #include "SIM_AirSim.h"
  17. #include <stdio.h>
  18. #include <arpa/inet.h>
  19. #include <errno.h>
  20. #include <AP_HAL/AP_HAL.h>
  21. #include <AP_Logger/AP_Logger.h>
  22. #include <AP_HAL/utility/replace.h>
  23. extern const AP_HAL::HAL& hal;
  24. using namespace SITL;
  25. AirSim::AirSim(const char *frame_str) :
  26. Aircraft(frame_str),
  27. sock(true)
  28. {
  29. printf("Starting SITL Airsim\n");
  30. }
  31. /*
  32. Create & set in/out socket
  33. */
  34. void AirSim::set_interface_ports(const char* address, const int port_in, const int port_out)
  35. {
  36. if (!sock.bind("0.0.0.0", port_in)) {
  37. printf("Unable to bind Airsim sensor_in socket at port %u - Error: %s\n",
  38. port_in, strerror(errno));
  39. return;
  40. }
  41. printf("Bind SITL sensor input at %s:%u\n", "127.0.0.1", port_in);
  42. sock.set_blocking(false);
  43. sock.reuseaddress();
  44. airsim_ip = address;
  45. airsim_control_port = port_out;
  46. airsim_sensor_port = port_in;
  47. printf("AirSim control interface set to %s:%u\n", airsim_ip, airsim_control_port);
  48. }
  49. /*
  50. Decode and send servos
  51. */
  52. void AirSim::send_servos(const struct sitl_input &input)
  53. {
  54. servo_packet pkt{0};
  55. for (uint8_t i=0; i<kArduCopterRotorControlCount; i++) {
  56. pkt.pwm[i] = input.servos[i];
  57. }
  58. ssize_t send_ret = sock.sendto(&pkt, sizeof(pkt), airsim_ip, airsim_control_port);
  59. if (send_ret != sizeof(pkt)) {
  60. if (send_ret <= 0) {
  61. printf("Unable to send servo output to %s:%u - Error: %s, Return value: %ld\n",
  62. airsim_ip, airsim_control_port, strerror(errno), send_ret);
  63. } else {
  64. printf("Sent %ld bytes instead of %ld bytes\n", send_ret, sizeof(pkt));
  65. }
  66. }
  67. }
  68. /*
  69. very simple JSON parser for sensor data
  70. called with pointer to one row of sensor data, nul terminated
  71. This parser does not do any syntax checking, and is not at all
  72. general purpose
  73. */
  74. bool AirSim::parse_sensors(const char *json)
  75. {
  76. // printf("%s\n", json);
  77. for (uint16_t i=0; i<ARRAY_SIZE(keytable); i++) {
  78. struct keytable &key = keytable[i];
  79. /* look for section header */
  80. const char *p = strstr(json, key.section);
  81. if (!p) {
  82. // we don't have this sensor
  83. continue;
  84. }
  85. p += strlen(key.section)+1;
  86. // find key inside section
  87. p = strstr(p, key.key);
  88. if (!p) {
  89. printf("Failed to find key %s/%s\n", key.section, key.key);
  90. return false;
  91. }
  92. p += strlen(key.key)+3;
  93. switch (key.type) {
  94. case DATA_UINT64:
  95. *((uint64_t *)key.ptr) = strtoul(p, nullptr, 10);
  96. break;
  97. case DATA_FLOAT:
  98. *((float *)key.ptr) = atof(p);
  99. break;
  100. case DATA_DOUBLE:
  101. *((double *)key.ptr) = atof(p);
  102. break;
  103. case DATA_VECTOR3F: {
  104. Vector3f *v = (Vector3f *)key.ptr;
  105. if (sscanf(p, "[%f, %f, %f]", &v->x, &v->y, &v->z) != 3) {
  106. printf("Failed to parse Vector3f for %s/%s\n", key.section, key.key);
  107. return false;
  108. }
  109. break;
  110. }
  111. case DATA_VECTOR3F_ARRAY: {
  112. // - array of floats that represent [x,y,z] coordinate for each point hit within the range
  113. // x0, y0, z0, x1, y1, z1, ..., xn, yn, zn
  114. // example: [23.1,0.677024,1.4784,-8.97607135772705,-8.976069450378418,-8.642673492431641e-07,]
  115. if (*p++ != '[') {
  116. return false;
  117. }
  118. uint16_t n = 0;
  119. struct vector3f_array *v = (struct vector3f_array *)key.ptr;
  120. while (true) {
  121. if (n >= v->length) {
  122. Vector3f *d = (Vector3f *)realloc(v->data, sizeof(Vector3f)*(n+1));
  123. if (d == nullptr) {
  124. return false;
  125. }
  126. v->data = d;
  127. v->length = n+1;
  128. }
  129. if (sscanf(p, "%f,%f,%f,", &v->data[n].x, &v->data[n].y, &v->data[n].z) != 3) {
  130. printf("Failed to parse Vector3f for %s/%s[%u]\n", key.section, key.key, n);
  131. return false;
  132. }
  133. n++;
  134. // Goto 3rd occurence of ,
  135. p = strchr(p,',');
  136. if (!p) {
  137. return false;
  138. }
  139. p++;
  140. p = strchr(p,',');
  141. if (!p) {
  142. return false;
  143. }
  144. p++;
  145. p = strchr(p,',');
  146. if (!p) {
  147. return false;
  148. }
  149. p++;
  150. // Reached end of point cloud
  151. if (p[0] == ']') {
  152. break;
  153. }
  154. }
  155. v->length = n;
  156. break;
  157. }
  158. case DATA_FLOAT_ARRAY: {
  159. // example: [18.0, 12.694079399108887]
  160. if (*p++ != '[') {
  161. return false;
  162. }
  163. uint16_t n = 0;
  164. struct float_array *v = (struct float_array *)key.ptr;
  165. while (true) {
  166. if (n >= v->length) {
  167. float *d = (float *)realloc(v->data, sizeof(float)*(n+1));
  168. if (d == nullptr) {
  169. return false;
  170. }
  171. v->data = d;
  172. v->length = n+1;
  173. }
  174. v->data[n] = atof(p);
  175. n++;
  176. p = strchr(p,',');
  177. if (!p) {
  178. break;
  179. }
  180. p++;
  181. }
  182. v->length = n;
  183. break;
  184. }
  185. }
  186. }
  187. return true;
  188. }
  189. /*
  190. Receive new sensor data from simulator
  191. This is a blocking function
  192. */
  193. void AirSim::recv_fdm()
  194. {
  195. // Receive sensor packet
  196. ssize_t ret = sock.recv(&sensor_buffer[sensor_buffer_len], sizeof(sensor_buffer)-sensor_buffer_len, 100);
  197. while (ret <= 0) {
  198. printf("No sensor message received - %s\n", strerror(errno));
  199. ret = sock.recv(&sensor_buffer[sensor_buffer_len], sizeof(sensor_buffer)-sensor_buffer_len, 100);
  200. }
  201. // convert '\n' into nul
  202. while (uint8_t *p = (uint8_t *)memchr(&sensor_buffer[sensor_buffer_len], '\n', ret)) {
  203. *p = 0;
  204. }
  205. sensor_buffer_len += ret;
  206. const uint8_t *p2 = (const uint8_t *)memrchr(sensor_buffer, 0, sensor_buffer_len);
  207. if (p2 == nullptr || p2 == sensor_buffer) {
  208. return;
  209. }
  210. const uint8_t *p1 = (const uint8_t *)memrchr(sensor_buffer, 0, p2 - sensor_buffer);
  211. if (p1 == nullptr) {
  212. return;
  213. }
  214. parse_sensors((const char *)(p1+1));
  215. memmove(sensor_buffer, p2, sensor_buffer_len - (p2 - sensor_buffer));
  216. sensor_buffer_len = sensor_buffer_len - (p2 - sensor_buffer);
  217. accel_body = Vector3f(state.imu.linear_acceleration[0],
  218. state.imu.linear_acceleration[1],
  219. state.imu.linear_acceleration[2]);
  220. gyro = Vector3f(state.imu.angular_velocity[0],
  221. state.imu.angular_velocity[1],
  222. state.imu.angular_velocity[2]);
  223. velocity_ef = Vector3f(state.velocity.world_linear_velocity[0],
  224. state.velocity.world_linear_velocity[1],
  225. state.velocity.world_linear_velocity[0]);
  226. location.lat = state.gps.lat * 1.0e7;
  227. location.lng = state.gps.lon * 1.0e7;
  228. location.alt = state.gps.alt * 100.0f;
  229. dcm.from_euler(state.pose.roll, state.pose.pitch, state.pose.yaw);
  230. if (last_timestamp) {
  231. int deltat = state.timestamp - last_timestamp;
  232. time_now_us += deltat;
  233. if (deltat > 0 && deltat < 100000) {
  234. if (average_frame_time < 1) {
  235. average_frame_time = deltat;
  236. }
  237. average_frame_time = average_frame_time * 0.98 + deltat * 0.02;
  238. }
  239. }
  240. scanner.points = state.lidar.points;
  241. rcin_chan_count = state.rc.rc_channels.length < 8 ? state.rc.rc_channels.length : 8;
  242. for (uint8_t i=0; i < rcin_chan_count; i++) {
  243. rcin[i] = state.rc.rc_channels.data[i];
  244. }
  245. #if 0
  246. AP::logger().Write("ASM1", "TimeUS,TUS,R,P,Y,GX,GY,GZ",
  247. "QQffffff",
  248. AP_HAL::micros64(),
  249. state.timestamp,
  250. degrees(state.pose.roll),
  251. degrees(state.pose.pitch),
  252. degrees(state.pose.yaw),
  253. degrees(gyro.x),
  254. degrees(gyro.y),
  255. degrees(gyro.z));
  256. Vector3f velocity_bf = dcm.transposed() * velocity_ef;
  257. position = home.get_distance_NED(location);
  258. AP::logger().Write("ASM2", "TimeUS,AX,AY,AZ,VX,VY,VZ,PX,PY,PZ,Alt,SD",
  259. "Qfffffffffff",
  260. AP_HAL::micros64(),
  261. accel_body.x,
  262. accel_body.y,
  263. accel_body.z,
  264. velocity_bf.x,
  265. velocity_bf.y,
  266. velocity_bf.z,
  267. position.x,
  268. position.y,
  269. position.z,
  270. state.gps.alt,
  271. velocity_ef.z);
  272. #endif
  273. last_timestamp = state.timestamp;
  274. }
  275. /*
  276. update the AirSim simulation by one time step
  277. */
  278. void AirSim::update(const struct sitl_input &input)
  279. {
  280. send_servos(input);
  281. recv_fdm();
  282. // update magnetic field
  283. update_mag_field_bf();
  284. report_FPS();
  285. }
  286. /*
  287. report frame rates
  288. */
  289. void AirSim::report_FPS(void)
  290. {
  291. if (frame_counter++ % 1000 == 0) {
  292. if (last_frame_count != 0) {
  293. printf("FPS avg=%.2f\n", 1.0e6/average_frame_time);
  294. }
  295. last_frame_count = state.timestamp;
  296. }
  297. }