SIM_Webots.cpp 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583
  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 Weboreceived 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 webots simulator
  15. */
  16. #include "SIM_Webots.h"
  17. #include <arpa/inet.h>
  18. #include <errno.h>
  19. #include <fcntl.h>
  20. #include <stdio.h>
  21. #include <stdarg.h>
  22. #include <sys/stat.h>
  23. #include <sys/types.h>
  24. #include <AP_HAL/AP_HAL.h>
  25. #include <AP_Logger/AP_Logger.h>
  26. #include "pthread.h"
  27. #include <AP_HAL/utility/replace.h>
  28. extern const AP_HAL::HAL& hal;
  29. using namespace SITL;
  30. static const struct {
  31. const char *name;
  32. float value;
  33. bool save;
  34. } sim_defaults[] = {
  35. { "AHRS_EKF_TYPE", 10 },
  36. { "INS_GYR_CAL", 0 },
  37. { "RC1_MIN", 1000, true },
  38. { "RC1_MAX", 2000, true },
  39. { "RC2_MIN", 1000, true },
  40. { "RC2_MAX", 2000, true },
  41. { "RC3_MIN", 1000, true },
  42. { "RC3_MAX", 2000, true },
  43. { "RC4_MIN", 1000, true },
  44. { "RC4_MAX", 2000, true },
  45. { "RC2_REVERSED", 1 }, // interlink has reversed rc2
  46. { "SERVO1_MIN", 1000 },
  47. { "SERVO1_MAX", 2000 },
  48. { "SERVO2_MIN", 1000 },
  49. { "SERVO2_MAX", 2000 },
  50. { "SERVO3_MIN", 1000 },
  51. { "SERVO3_MAX", 2000 },
  52. { "SERVO4_MIN", 1000 },
  53. { "SERVO4_MAX", 2000 },
  54. { "SERVO5_MIN", 1000 },
  55. { "SERVO5_MAX", 2000 },
  56. { "SERVO6_MIN", 1000 },
  57. { "SERVO6_MAX", 2000 },
  58. { "SERVO6_MIN", 1000 },
  59. { "SERVO6_MAX", 2000 },
  60. { "INS_ACC2OFFS_X", 0.001 },
  61. { "INS_ACC2OFFS_Y", 0.001 },
  62. { "INS_ACC2OFFS_Z", 0.001 },
  63. { "INS_ACC2SCAL_X", 1.001 },
  64. { "INS_ACC2SCAL_Y", 1.001 },
  65. { "INS_ACC2SCAL_Z", 1.001 },
  66. { "INS_ACCOFFS_X", 0.001 },
  67. { "INS_ACCOFFS_Y", 0.001 },
  68. { "INS_ACCOFFS_Z", 0.001 },
  69. { "INS_ACCSCAL_X", 1.001 },
  70. { "INS_ACCSCAL_Y", 1.001 },
  71. { "INS_ACCSCAL_Z", 1.001 },
  72. };
  73. Webots::Webots(const char *frame_str) :
  74. Aircraft(frame_str)
  75. {
  76. use_time_sync = true;
  77. rate_hz = 4000;
  78. char *saveptr = nullptr;
  79. char *s = strdup(frame_str);
  80. char *frame_option = strtok_r(s, ":", &saveptr);
  81. char *args1 = strtok_r(nullptr, ":", &saveptr);
  82. char *args2 = strtok_r(nullptr, ":", &saveptr);
  83. /*
  84. allow setting of IP, sensors port and control port
  85. format morse:IPADDRESS:SENSORS_PORT:CONTROL_PORT
  86. */
  87. if (args1) {
  88. webots_ip = args1;
  89. }
  90. if (args2) {
  91. webots_sensors_port = atoi(args2);
  92. }
  93. if (strstr(frame_option, "-rover")) {
  94. output_type = OUTPUT_ROVER;
  95. } else if (strstr(frame_option, "-quad")) {
  96. output_type = OUTPUT_QUAD;
  97. } else if (strstr(frame_option, "-pwm")) {
  98. output_type = OUTPUT_PWM;
  99. } else {
  100. // default to rover
  101. output_type = OUTPUT_ROVER;
  102. }
  103. for (uint8_t i=0; i<ARRAY_SIZE(sim_defaults); i++) {
  104. AP_Param::set_default_by_name(sim_defaults[i].name, sim_defaults[i].value);
  105. if (sim_defaults[i].save) {
  106. enum ap_var_type ptype;
  107. AP_Param *p = AP_Param::find(sim_defaults[i].name, &ptype);
  108. if (!p->configured()) {
  109. p->save();
  110. }
  111. }
  112. }
  113. printf("Started Webots with %s:%u type %u\n",
  114. webots_ip, webots_sensors_port,
  115. (unsigned)output_type);
  116. }
  117. /*
  118. very simple JSON parser for sensor data
  119. called with pointer to one row of sensor data, nul terminated
  120. This parser does not do any syntax checking, and is not at all
  121. general purpose
  122. {"timestamp": 1563474924.817575,
  123. "vehicle.imu": {"timestamp": 1563474924.8009083,
  124. "angular_velocity": [2.319516170246061e-06, -3.5830129263558774e-07, 7.009341995711793e-09],
  125. "linear_acceleration": [0.005075275432318449, 0.22471635043621063, 9.80748176574707],
  126. "magnetic_field": [23088.65625, 3875.89453125, -53204.51171875]},
  127. "vehicle.gps": {"timestamp": 1563474924.8009083, "x": 5.386466364143416e-05, "y": -0.0010969983413815498, "z": 0.03717954829335213},
  128. "vehicle.velocity": {"timestamp": 1563474924.8009083,
  129. "linear_velocity": [4.818238585890811e-10, 2.1333558919423012e-08, 9.310780910709582e-07],
  130. "angular_velocity": [2.319516170246061e-06, -3.5830129263558774e-07, 7.009341995711793e-09],
  131. "world_linear_velocity": [5.551115123125783e-17, 0.0, 9.313225746154785e-07]},
  132. "vehicle.pose": {"timestamp": 1563474924.8009083,
  133. "x": 5.386466364143416e-05, "y": -0.0010969983413815498, "z": 0.03717954829335213,
  134. "yaw": 7.137723878258839e-05, "pitch": -0.0005173543468117714, "roll": 0.022908739745616913}}
  135. */
  136. bool Webots::parse_sensors(const char *json)
  137. {
  138. //printf("%s\n", json);
  139. ///*
  140. for (uint16_t i=0; i<ARRAY_SIZE(keytable); i++) {
  141. struct keytable &key = keytable[i];
  142. //printf("search %s/%s\n", key.section, key.key);
  143. // look for section header
  144. const char *p = strstr(json, key.section);
  145. if (!p) {
  146. // we don't have this sensor
  147. continue;
  148. }
  149. p += strlen(key.section)+1;
  150. // find key inside section
  151. p = strstr(p, key.key);
  152. if (!p) {
  153. printf("Failed to find key %s/%s\n", key.section, key.key);
  154. return false;
  155. }
  156. p += strlen(key.key)+3;
  157. switch (key.type) {
  158. case DATA_FLOAT:
  159. *((float *)key.ptr) = atof(p);
  160. //printf("GOT %s/%s value: %f\n", key.section, key.key, *((float *)key.ptr));
  161. break;
  162. case DATA_DOUBLE:
  163. *((double *)key.ptr) = atof(p);
  164. //printf("GOT %s/%s value: %f\n", key.section, key.key, *((double *)key.ptr));
  165. break;
  166. case DATA_VECTOR3F: {
  167. Vector3f *v = (Vector3f *)key.ptr;
  168. if (sscanf(p, "[%f, %f, %f]", &v->x, &v->y, &v->z) != 3) {
  169. printf("Failed to parse Vector3f for %s %s/%s\n",p, key.section, key.key);
  170. //printf("Failed to parse Vector3f for %s/%s\n", key.section, key.key);
  171. return false;
  172. }
  173. else
  174. {
  175. //printf("GOT %s/%s [%f, %f, %f]\n", key.section, key.key, v->x, v->y, v->z);
  176. }
  177. break;
  178. }
  179. case DATA_VECTOR3F_ARRAY: {
  180. // example: [[0.0, 0.0, 0.0], [-8.97607135772705, -8.976069450378418, -8.642673492431641e-07]]
  181. if (*p++ != '[') {
  182. return false;
  183. }
  184. uint16_t n = 0;
  185. struct vector3f_array *v = (struct vector3f_array *)key.ptr;
  186. while (true) {
  187. if (n >= v->length) {
  188. Vector3f *d = (Vector3f *)realloc(v->data, sizeof(Vector3f)*(n+1));
  189. if (d == nullptr) {
  190. return false;
  191. }
  192. v->data = d;
  193. v->length = n+1;
  194. }
  195. if (sscanf(p, "[%f, %f, %f]", &v->data[n].x, &v->data[n].y, &v->data[n].z) != 3) {
  196. //printf("Failed to parse Vector3f for %s %s/%s[%u]\n",p, key.section, key.key, n);
  197. //printf("Failed to parse Vector3f for %s/%s[%u]\n", key.section, key.key, n);
  198. return false;
  199. }
  200. else
  201. {
  202. //printf("GOT %s/%s [%f, %f, %f]\n", key.section, key.key, v->data[n].x, v->data[n].y, v->data[n].z);
  203. }
  204. n++;
  205. p = strchr(p,']');
  206. if (!p) {
  207. return false;
  208. }
  209. p++;
  210. if (p[0] != ',') {
  211. break;
  212. }
  213. if (p[1] != ' ') {
  214. return false;
  215. }
  216. p += 2;
  217. }
  218. if (p[0] != ']') {
  219. return false;
  220. }
  221. v->length = n;
  222. break;
  223. }
  224. case DATA_FLOAT_ARRAY: {
  225. // example: [18.0, 12.694079399108887]
  226. if (*p++ != '[') {
  227. return false;
  228. }
  229. uint16_t n = 0;
  230. struct float_array *v = (struct float_array *)key.ptr;
  231. while (true) {
  232. if (n >= v->length) {
  233. float *d = (float *)realloc(v->data, sizeof(float)*(n+1));
  234. if (d == nullptr) {
  235. return false;
  236. }
  237. v->data = d;
  238. v->length = n+1;
  239. }
  240. v->data[n] = atof(p);
  241. n++;
  242. p = strchr(p,',');
  243. if (!p) {
  244. break;
  245. }
  246. p++;
  247. }
  248. v->length = n;
  249. break;
  250. }
  251. }
  252. }
  253. // */
  254. socket_frame_counter++;
  255. return true;
  256. }
  257. /*
  258. connect to the required sockets
  259. */
  260. bool Webots::connect_sockets(void)
  261. {
  262. if (!sim_sock) {
  263. sim_sock = new SocketAPM(false);
  264. if (!sim_sock) {
  265. AP_HAL::panic("Out of memory for sensors socket");
  266. }
  267. if (!sim_sock->connect(webots_ip, webots_sensors_port)) {
  268. usleep(100000);
  269. if (connect_counter++ == 20) {
  270. printf("Waiting to connect to sensors control on %s:%u\n",
  271. webots_ip, webots_sensors_port);
  272. connect_counter = 0;
  273. }
  274. delete sim_sock;
  275. sim_sock = nullptr;
  276. return false;
  277. }
  278. sim_sock->reuseaddress();
  279. printf("Sensors connected\n");
  280. }
  281. return true;
  282. }
  283. /*
  284. get any new data from the sensors socket
  285. */
  286. bool Webots::sensors_receive(void)
  287. {
  288. ssize_t ret = sim_sock->recv(&sensor_buffer[sensor_buffer_len], sizeof(sensor_buffer)-sensor_buffer_len, 0);
  289. if (ret <= 0) {
  290. no_data_counter++;
  291. if (no_data_counter == 1000) {
  292. no_data_counter = 0;
  293. delete sim_sock;
  294. sim_sock = nullptr;
  295. }
  296. return false;
  297. }
  298. no_data_counter = 0;
  299. // convert '\n' into nul
  300. while (uint8_t *p = (uint8_t *)memchr(&sensor_buffer[sensor_buffer_len], '\n', ret)) {
  301. *p = 0;
  302. }
  303. sensor_buffer_len += ret;
  304. const uint8_t *p2 = (const uint8_t *)memrchr(sensor_buffer, 0, sensor_buffer_len);
  305. if (p2 == nullptr || p2 == sensor_buffer) {
  306. return false;
  307. }
  308. const uint8_t *p1 = (const uint8_t *)memrchr(sensor_buffer, 0, p2 - sensor_buffer);
  309. if (p1 == nullptr) {
  310. return false;
  311. }
  312. bool parse_ok = parse_sensors((const char *)(p1+1));
  313. memmove(sensor_buffer, p2, sensor_buffer_len - (p2 - sensor_buffer));
  314. sensor_buffer_len = sensor_buffer_len - (p2 - sensor_buffer);
  315. return parse_ok;
  316. }
  317. /*
  318. output control command assuming skid-steering rover
  319. */
  320. void Webots::output_rover(const struct sitl_input &input)
  321. {
  322. const float motor1 = 2*((input.servos[0]-1000)/1000.0f - 0.5f);
  323. const float motor2 = 2*((input.servos[2]-1000)/1000.0f - 0.5f);
  324. // construct a JSON packet for v and w
  325. char buf[200];
  326. const int len = snprintf(buf, sizeof(buf)-1, "{\"rover\": [%f, %f], \"wnd\": [%f, %f, %f, %f]}\n",
  327. motor1, motor2,
  328. input.wind.speed, wind_ef.x, wind_ef.y, wind_ef.z);
  329. buf[len] = 0;
  330. sim_sock->send(buf, len);
  331. }
  332. /*
  333. output control command assuming a 4 channel quad
  334. */
  335. void Webots::output_quad(const struct sitl_input &input)
  336. {
  337. const float max_thrust = 1.0;
  338. float motors[4];
  339. for (uint8_t i=0; i<4; i++) {
  340. //return a filtered servo input as a value from 0 to 1
  341. //servo is assumed to be 1000 to 2000
  342. motors[i] = constrain_float(((input.servos[i]-1000)/1000.0f) * max_thrust, 0, max_thrust);
  343. }
  344. const float &m_right = motors[0];
  345. const float &m_left = motors[1];
  346. const float &m_front = motors[2];
  347. const float &m_back = motors[3];
  348. // quad format in Webots is:
  349. // m1: front
  350. // m2: right
  351. // m3: back
  352. // m4: left
  353. // construct a JSON packet for motors
  354. char buf[200];
  355. const int len = snprintf(buf, sizeof(buf)-1, "{\"eng\": [%.3f, %.3f, %.3f, %.3f], \"wnd\": [%f, %3.1f, %1.1f, %2.1f]}\n",
  356. m_front, m_right, m_back, m_left,
  357. input.wind.speed, wind_ef.x, wind_ef.y, wind_ef.z);
  358. buf[len] = 0;
  359. sim_sock->send(buf, len);
  360. }
  361. /*
  362. output all 16 channels as PWM values. This allows for general
  363. control of a robot
  364. */
  365. void Webots::output_pwm(const struct sitl_input &input)
  366. {
  367. char buf[200];
  368. const int len = snprintf(buf, sizeof(buf)-1, "{\"pwm\": [%u, %uf, %u, %u, %u, %uf, %u, %u, %u, %uf, %u, %u, %u, %uf, %u, %u], \"wnd\": [%f, %f, %f, %f]}\n",
  369. input.servos[0], input.servos[1], input.servos[2], input.servos[3],
  370. input.servos[4], input.servos[5], input.servos[6], input.servos[7],
  371. input.servos[8], input.servos[9], input.servos[10], input.servos[11],
  372. input.servos[12], input.servos[13], input.servos[14], input.servos[15],
  373. input.wind.speed, wind_ef.x, wind_ef.y, wind_ef.z);
  374. buf[len ] = 0;
  375. sim_sock->send(buf, len);
  376. }
  377. void Webots::output (const struct sitl_input &input)
  378. {
  379. switch (output_type) {
  380. case OUTPUT_ROVER:
  381. output_rover(input);
  382. break;
  383. case OUTPUT_QUAD:
  384. output_quad(input);
  385. break;
  386. case OUTPUT_PWM:
  387. output_pwm(input);
  388. break;
  389. }
  390. }
  391. /*
  392. update the Webots simulation by one time step
  393. */
  394. void Webots::update(const struct sitl_input &input)
  395. {
  396. if (!connect_sockets()) {
  397. return;
  398. }
  399. last_state = state;
  400. const bool valid = sensors_receive();
  401. if (valid) {
  402. // update average frame time used for extrapolation
  403. double dt = constrain_float(state.timestamp - last_state.timestamp, 0.001, 1.0/50);
  404. if (average_frame_time_s < 1.0e-6) {
  405. //if average is too small take the current dt as a good start.
  406. average_frame_time_s = dt;
  407. }
  408. // this is complementry filter for updating average.
  409. average_frame_time_s = average_frame_time_s * 0.98 + dt * 0.02;
  410. }
  411. // again measure dt as dt_s but with no constraints....
  412. double dt_s = state.timestamp - last_state.timestamp;
  413. if (dt_s < 0 || dt_s > 1) {
  414. // cope with restarting while connected
  415. initial_time_s = time_now_us * 1.0e-6f;
  416. return;
  417. }
  418. if (dt_s < 0.00001f) {
  419. float delta_time = 0.001;
  420. // don't go past the next expected frame
  421. if (delta_time + extrapolated_s > average_frame_time_s) {
  422. delta_time = average_frame_time_s - extrapolated_s;
  423. }
  424. // check if extrapolation_s duration is longer than average_frame_time_s
  425. if (delta_time <= 0) {
  426. // dont extrapolate anymore untill there is valid data with long-enough dt_s
  427. usleep(1000);
  428. return;
  429. }
  430. // extrapolated_s duration is safe. keep on extrapolation.
  431. time_now_us += delta_time * 1.0e6;
  432. extrapolate_sensors(delta_time);
  433. update_position();
  434. //update body magnetic field from position and rotation
  435. update_mag_field_bf();
  436. usleep(delta_time * 1.0e6);
  437. extrapolated_s += delta_time;
  438. //output(input);
  439. report_FPS();
  440. return;
  441. }
  442. if (valid)
  443. {
  444. // reset extrapolation duration.
  445. extrapolated_s = 0;
  446. if (initial_time_s <= 0) {
  447. dt_s = 0.001f;
  448. initial_time_s = state.timestamp - dt_s;
  449. }
  450. // convert from state variables to ardupilot conventions
  451. dcm.from_euler(state.pose.roll, state.pose.pitch, -state.pose.yaw);
  452. gyro = Vector3f(state.imu.angular_velocity[0] ,
  453. state.imu.angular_velocity[1] ,
  454. -state.imu.angular_velocity[2] );
  455. accel_body = Vector3f(+state.imu.linear_acceleration[0],
  456. +state.imu.linear_acceleration[1],
  457. -state.imu.linear_acceleration[2]);
  458. velocity_ef = Vector3f(+state.velocity.world_linear_velocity[0],
  459. +state.velocity.world_linear_velocity[1],
  460. -state.velocity.world_linear_velocity[2]);
  461. position = Vector3f(state.gps.x, state.gps.y, -state.gps.z);
  462. // limit to 16G to match pixhawk1
  463. float a_limit = GRAVITY_MSS*16;
  464. accel_body.x = constrain_float(accel_body.x, -a_limit, a_limit);
  465. accel_body.y = constrain_float(accel_body.y, -a_limit, a_limit);
  466. accel_body.z = constrain_float(accel_body.z, -a_limit, a_limit);
  467. // fill in laser scanner results, if available
  468. scanner.points = state.scanner.points;
  469. scanner.ranges = state.scanner.ranges;
  470. update_position();
  471. uint64_t new_time_us = (state.timestamp - initial_time_s)*1.0e6;
  472. if (new_time_us < time_now_us) {
  473. uint64_t dt_us = time_now_us - new_time_us;
  474. if (dt_us > 500000) {
  475. // time going backwards
  476. time_now_us = new_time_us;
  477. }
  478. } else {
  479. // update SITL time with webots time.
  480. time_now_us = new_time_us;
  481. }
  482. time_advance();
  483. // update magnetic field
  484. update_mag_field_bf();
  485. update_wind (input);
  486. output(input);
  487. report_FPS();
  488. }
  489. }
  490. /*
  491. report frame rates
  492. */
  493. void Webots::report_FPS(void)
  494. {
  495. if (frame_counter++ % 1000 == 0) {
  496. if (!is_zero(last_frame_count_s)) {
  497. uint64_t frames = socket_frame_counter - last_socket_frame_counter;
  498. last_socket_frame_counter = socket_frame_counter;
  499. double dt = state.timestamp - last_frame_count_s;
  500. printf("%.2f/%.2f FPS avg=%.2f\n",
  501. frames / dt, 1000 / dt, 1.0/average_frame_time_s);
  502. } else {
  503. printf("Initial position %f %f %f\n", position.x, position.y, position.z);
  504. }
  505. last_frame_count_s = state.timestamp;
  506. }
  507. }