SIM_Morse.cpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629
  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 morse simulator
  15. */
  16. #include "SIM_Morse.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. Morse::Morse(const char *frame_str) :
  74. Aircraft(frame_str)
  75. {
  76. char *saveptr = nullptr;
  77. char *s = strdup(frame_str);
  78. char *frame_option = strtok_r(s, ":", &saveptr);
  79. char *args1 = strtok_r(nullptr, ":", &saveptr);
  80. char *args2 = strtok_r(nullptr, ":", &saveptr);
  81. char *args3 = strtok_r(nullptr, ":", &saveptr);
  82. /*
  83. allow setting of IP, sensors port and control port
  84. format morse:IPADDRESS:SENSORS_PORT:CONTROL_PORT
  85. */
  86. if (args1) {
  87. morse_ip = args1;
  88. }
  89. if (args2) {
  90. morse_sensors_port = atoi(args2);
  91. morse_control_port = morse_sensors_port+1;
  92. }
  93. if (args3) {
  94. morse_control_port = atoi(args3);
  95. }
  96. if (strstr(frame_option, "-rover")) {
  97. output_type = OUTPUT_ROVER;
  98. } else if (strstr(frame_option, "-quad")) {
  99. output_type = OUTPUT_QUAD;
  100. } else if (strstr(frame_option, "-pwm")) {
  101. output_type = OUTPUT_PWM;
  102. } else {
  103. // default to rover
  104. output_type = OUTPUT_ROVER;
  105. }
  106. for (uint8_t i=0; i<ARRAY_SIZE(sim_defaults); i++) {
  107. AP_Param::set_default_by_name(sim_defaults[i].name, sim_defaults[i].value);
  108. if (sim_defaults[i].save) {
  109. enum ap_var_type ptype;
  110. AP_Param *p = AP_Param::find(sim_defaults[i].name, &ptype);
  111. if (!p->configured()) {
  112. p->save();
  113. }
  114. }
  115. }
  116. printf("Started Morse with %s:%u:%u type %u\n",
  117. morse_ip, morse_sensors_port, morse_control_port,
  118. (unsigned)output_type);
  119. }
  120. /*
  121. very simple JSON parser for sensor data
  122. called with pointer to one row of sensor data, nul terminated
  123. This parser does not do any syntax checking, and is not at all
  124. general purpose
  125. */
  126. bool Morse::parse_sensors(const char *json)
  127. {
  128. //printf("%s\n", json);
  129. for (uint16_t i=0; i<ARRAY_SIZE(keytable); i++) {
  130. struct keytable &key = keytable[i];
  131. /* look for section header */
  132. const char *p = strstr(json, key.section);
  133. if (!p) {
  134. // we don't have this sensor
  135. continue;
  136. }
  137. p += strlen(key.section)+1;
  138. // find key inside section
  139. p = strstr(p, key.key);
  140. if (!p) {
  141. printf("Failed to find key %s/%s\n", key.section, key.key);
  142. return false;
  143. }
  144. p += strlen(key.key)+3;
  145. switch (key.type) {
  146. case DATA_FLOAT:
  147. *((float *)key.ptr) = atof(p);
  148. break;
  149. case DATA_DOUBLE:
  150. *((double *)key.ptr) = atof(p);
  151. break;
  152. case DATA_VECTOR3F: {
  153. Vector3f *v = (Vector3f *)key.ptr;
  154. if (sscanf(p, "[%f, %f, %f]", &v->x, &v->y, &v->z) != 3) {
  155. printf("Failed to parse Vector3f for %s/%s\n", key.section, key.key);
  156. return false;
  157. }
  158. break;
  159. }
  160. case DATA_VECTOR3F_ARRAY: {
  161. // example: [[0.0, 0.0, 0.0], [-8.97607135772705, -8.976069450378418, -8.642673492431641e-07]]
  162. if (*p++ != '[') {
  163. return false;
  164. }
  165. uint16_t n = 0;
  166. struct vector3f_array *v = (struct vector3f_array *)key.ptr;
  167. while (true) {
  168. if (n >= v->length) {
  169. Vector3f *d = (Vector3f *)realloc(v->data, sizeof(Vector3f)*(n+1));
  170. if (d == nullptr) {
  171. return false;
  172. }
  173. v->data = d;
  174. v->length = n+1;
  175. }
  176. if (sscanf(p, "[%f, %f, %f]", &v->data[n].x, &v->data[n].y, &v->data[n].z) != 3) {
  177. printf("Failed to parse Vector3f for %s/%s[%u]\n", key.section, key.key, n);
  178. return false;
  179. }
  180. n++;
  181. p = strchr(p,']');
  182. if (!p) {
  183. return false;
  184. }
  185. p++;
  186. if (p[0] != ',') {
  187. break;
  188. }
  189. if (p[1] != ' ') {
  190. return false;
  191. }
  192. p += 2;
  193. }
  194. if (p[0] != ']') {
  195. return false;
  196. }
  197. v->length = n;
  198. break;
  199. }
  200. case DATA_FLOAT_ARRAY: {
  201. // example: [18.0, 12.694079399108887]
  202. if (*p++ != '[') {
  203. return false;
  204. }
  205. uint16_t n = 0;
  206. struct float_array *v = (struct float_array *)key.ptr;
  207. while (true) {
  208. if (n >= v->length) {
  209. float *d = (float *)realloc(v->data, sizeof(float)*(n+1));
  210. if (d == nullptr) {
  211. return false;
  212. }
  213. v->data = d;
  214. v->length = n+1;
  215. }
  216. v->data[n] = atof(p);
  217. n++;
  218. p = strchr(p,',');
  219. if (!p) {
  220. break;
  221. }
  222. p++;
  223. }
  224. v->length = n;
  225. break;
  226. }
  227. }
  228. }
  229. socket_frame_counter++;
  230. return true;
  231. }
  232. /*
  233. connect to the required sockets
  234. */
  235. bool Morse::connect_sockets(void)
  236. {
  237. if (!sensors_sock) {
  238. sensors_sock = new SocketAPM(false);
  239. if (!sensors_sock) {
  240. AP_HAL::panic("Out of memory for sensors socket");
  241. }
  242. if (!sensors_sock->connect(morse_ip, morse_sensors_port)) {
  243. usleep(100000);
  244. if (connect_counter++ == 20) {
  245. printf("Waiting to connect to sensors control on %s:%u\n",
  246. morse_ip, morse_sensors_port);
  247. connect_counter = 0;
  248. }
  249. delete sensors_sock;
  250. sensors_sock = nullptr;
  251. return false;
  252. }
  253. sensors_sock->reuseaddress();
  254. printf("Sensors connected\n");
  255. }
  256. if (!control_sock) {
  257. control_sock = new SocketAPM(false);
  258. if (!control_sock) {
  259. AP_HAL::panic("Out of memory for control socket");
  260. }
  261. if (!control_sock->connect(morse_ip, morse_control_port)) {
  262. usleep(100000);
  263. if (connect_counter++ == 20) {
  264. printf("Waiting to connect to control control on %s:%u\n",
  265. morse_ip, morse_control_port);
  266. connect_counter = 0;
  267. }
  268. delete control_sock;
  269. control_sock = nullptr;
  270. return false;
  271. }
  272. control_sock->reuseaddress();
  273. printf("Control connected\n");
  274. }
  275. return true;
  276. }
  277. /*
  278. get any new data from the sensors socket
  279. */
  280. bool Morse::sensors_receive(void)
  281. {
  282. ssize_t ret = sensors_sock->recv(&sensor_buffer[sensor_buffer_len], sizeof(sensor_buffer)-sensor_buffer_len, 0);
  283. if (ret <= 0) {
  284. no_data_counter++;
  285. if (no_data_counter == 1000) {
  286. no_data_counter = 0;
  287. delete sensors_sock;
  288. delete control_sock;
  289. sensors_sock = nullptr;
  290. control_sock = nullptr;
  291. }
  292. return false;
  293. }
  294. no_data_counter = 0;
  295. // convert '\n' into nul
  296. while (uint8_t *p = (uint8_t *)memchr(&sensor_buffer[sensor_buffer_len], '\n', ret)) {
  297. *p = 0;
  298. }
  299. sensor_buffer_len += ret;
  300. const uint8_t *p2 = (const uint8_t *)memrchr(sensor_buffer, 0, sensor_buffer_len);
  301. if (p2 == nullptr || p2 == sensor_buffer) {
  302. return false;
  303. }
  304. const uint8_t *p1 = (const uint8_t *)memrchr(sensor_buffer, 0, p2 - sensor_buffer);
  305. if (p1 == nullptr) {
  306. return false;
  307. }
  308. bool parse_ok = parse_sensors((const char *)(p1+1));
  309. memmove(sensor_buffer, p2, sensor_buffer_len - (p2 - sensor_buffer));
  310. sensor_buffer_len = sensor_buffer_len - (p2 - sensor_buffer);
  311. return parse_ok;
  312. }
  313. /*
  314. output control command assuming skid-steering rover
  315. */
  316. void Morse::output_rover(const struct sitl_input &input)
  317. {
  318. float motor1 = 2*((input.servos[0]-1000)/1000.0f - 0.5f);
  319. float motor2 = 2*((input.servos[2]-1000)/1000.0f - 0.5f);
  320. const float steer_rate_max_dps = 60;
  321. const float max_speed = 2;
  322. const float steering_rps = (motor1 - motor2) * radians(steer_rate_max_dps);
  323. const float speed_ms = 0.5*(motor1 + motor2) * max_speed;
  324. // construct a JSON packet for v and w
  325. char buf[60];
  326. snprintf(buf, sizeof(buf)-1, "{\"v\": %.3f, \"w\": %.2f}\n",
  327. speed_ms, -steering_rps);
  328. buf[sizeof(buf)-1] = 0;
  329. control_sock->send(buf, strlen(buf));
  330. }
  331. /*
  332. output control command assuming a 4 channel quad
  333. */
  334. void Morse::output_quad(const struct sitl_input &input)
  335. {
  336. const float max_thrust = 1500;
  337. float motors[4];
  338. for (uint8_t i=0; i<4; i++) {
  339. motors[i] = constrain_float(((input.servos[i]-1000)/1000.0f) * max_thrust, 0, max_thrust);
  340. }
  341. const float &m_right = motors[0];
  342. const float &m_left = motors[1];
  343. const float &m_front = motors[2];
  344. const float &m_back = motors[3];
  345. // quad format in Morse is:
  346. // m1: back
  347. // m2: right
  348. // m3: front
  349. // m4: left
  350. // construct a JSON packet for motors
  351. char buf[60];
  352. snprintf(buf, sizeof(buf)-1, "{\"engines\": [%.3f, %.3f, %.3f, %.3f]}\n",
  353. m_back, m_right, m_front, m_left);
  354. buf[sizeof(buf)-1] = 0;
  355. control_sock->send(buf, strlen(buf));
  356. }
  357. /*
  358. output all 16 channels as PWM values. This allows for general
  359. control of a robot
  360. */
  361. void Morse::output_pwm(const struct sitl_input &input)
  362. {
  363. char buf[200];
  364. snprintf(buf, sizeof(buf)-1, "{\"pwm\": [%u, %uf, %u, %u, %u, %uf, %u, %u, %u, %uf, %u, %u, %u, %uf, %u, %u]}\n",
  365. input.servos[0], input.servos[1], input.servos[2], input.servos[3],
  366. input.servos[4], input.servos[5], input.servos[6], input.servos[7],
  367. input.servos[8], input.servos[9], input.servos[10], input.servos[11],
  368. input.servos[12], input.servos[13], input.servos[14], input.servos[15]);
  369. buf[sizeof(buf)-1] = 0;
  370. control_sock->send(buf, strlen(buf));
  371. }
  372. /*
  373. update the Morse simulation by one time step
  374. */
  375. void Morse::update(const struct sitl_input &input)
  376. {
  377. if (!connect_sockets()) {
  378. return;
  379. }
  380. last_state = state;
  381. if (sensors_receive()) {
  382. // update average frame time used for extrapolation
  383. double dt = constrain_float(state.timestamp - last_state.timestamp, 0.001, 1.0/50);
  384. if (average_frame_time_s < 1.0e-6) {
  385. average_frame_time_s = dt;
  386. }
  387. average_frame_time_s = average_frame_time_s * 0.98 + dt * 0.02;
  388. }
  389. double dt_s = state.timestamp - last_state.timestamp;
  390. if (dt_s < 0 || dt_s > 1) {
  391. // cope with restarting while connected
  392. initial_time_s = time_now_us * 1.0e-6f;
  393. last_time_s = state.timestamp;
  394. return;
  395. }
  396. if (dt_s < 0.00001f) {
  397. float delta_time = 0.001;
  398. // don't go past the next expected frame
  399. if (delta_time + extrapolated_s > average_frame_time_s) {
  400. delta_time = average_frame_time_s - extrapolated_s;
  401. }
  402. if (delta_time <= 0) {
  403. usleep(1000);
  404. return;
  405. }
  406. time_now_us += delta_time * 1.0e6;
  407. extrapolate_sensors(delta_time);
  408. update_position();
  409. update_mag_field_bf();
  410. usleep(delta_time*1.0e6);
  411. extrapolated_s += delta_time;
  412. report_FPS();
  413. return;
  414. }
  415. extrapolated_s = 0;
  416. if (initial_time_s <= 0) {
  417. dt_s = 0.001f;
  418. initial_time_s = state.timestamp - dt_s;
  419. }
  420. // convert from state variables to ardupilot conventions
  421. dcm.from_euler(state.pose.roll, -state.pose.pitch, -state.pose.yaw);
  422. gyro = Vector3f(state.imu.angular_velocity[0],
  423. -state.imu.angular_velocity[1],
  424. -state.imu.angular_velocity[2]);
  425. velocity_ef = Vector3f(state.velocity.world_linear_velocity[0],
  426. -state.velocity.world_linear_velocity[1],
  427. -state.velocity.world_linear_velocity[2]);
  428. position = Vector3f(state.gps.x, -state.gps.y, -state.gps.z);
  429. // Morse IMU accel is NEU, convert to NED
  430. accel_body = Vector3f(state.imu.linear_acceleration[0],
  431. -state.imu.linear_acceleration[1],
  432. -state.imu.linear_acceleration[2]);
  433. // limit to 16G to match pixhawk1
  434. float a_limit = GRAVITY_MSS*16;
  435. accel_body.x = constrain_float(accel_body.x, -a_limit, a_limit);
  436. accel_body.y = constrain_float(accel_body.y, -a_limit, a_limit);
  437. accel_body.z = constrain_float(accel_body.z, -a_limit, a_limit);
  438. // fill in laser scanner results, if available
  439. scanner.points = state.scanner.points;
  440. scanner.ranges = state.scanner.ranges;
  441. update_position();
  442. time_advance();
  443. uint64_t new_time_us = (state.timestamp - initial_time_s)*1.0e6;
  444. if (new_time_us < time_now_us) {
  445. uint64_t dt_us = time_now_us - new_time_us;
  446. if (dt_us > 500000) {
  447. // time going backwards
  448. time_now_us = new_time_us;
  449. }
  450. } else {
  451. time_now_us = new_time_us;
  452. }
  453. last_time_s = state.timestamp;
  454. // update magnetic field
  455. update_mag_field_bf();
  456. switch (output_type) {
  457. case OUTPUT_ROVER:
  458. output_rover(input);
  459. break;
  460. case OUTPUT_QUAD:
  461. output_quad(input);
  462. break;
  463. case OUTPUT_PWM:
  464. output_pwm(input);
  465. break;
  466. }
  467. report_FPS();
  468. send_report();
  469. }
  470. /*
  471. report frame rates
  472. */
  473. void Morse::report_FPS(void)
  474. {
  475. if (frame_counter++ % 1000 == 0) {
  476. if (!is_zero(last_frame_count_s)) {
  477. uint64_t frames = socket_frame_counter - last_socket_frame_counter;
  478. last_socket_frame_counter = socket_frame_counter;
  479. double dt = state.timestamp - last_frame_count_s;
  480. printf("%.2f/%.2f FPS avg=%.2f\n",
  481. frames / dt, 1000 / dt, 1.0/average_frame_time_s);
  482. } else {
  483. printf("Initial position %f %f %f\n", position.x, position.y, position.z);
  484. }
  485. last_frame_count_s = state.timestamp;
  486. }
  487. }
  488. /*
  489. send a report to the vehicle control code over MAVLink
  490. */
  491. void Morse::send_report(void)
  492. {
  493. const uint32_t now = AP_HAL::millis();
  494. #if defined(__CYGWIN__) || defined(__CYGWIN64__)
  495. if (now < 10000) {
  496. // don't send lidar reports until 10s after startup. This
  497. // avoids a windows threading issue with non-blocking sockets
  498. // and the initial wait on uartA
  499. return;
  500. }
  501. #endif
  502. // this is usually loopback
  503. if (!mavlink.connected && mav_socket.connect(mavlink_loopback_address, mavlink_loopback_port)) {
  504. ::printf("Morse MAVLink loopback connected to %s:%u\n", mavlink_loopback_address, (unsigned)mavlink_loopback_port);
  505. mavlink.connected = true;
  506. }
  507. if (!mavlink.connected) {
  508. return;
  509. }
  510. // send a OBSTACLE_DISTANCE messages at 15 Hz
  511. if (now - send_report_last_ms >= (1000/15) && scanner.points.length == scanner.ranges.length && scanner.points.length > 0) {
  512. send_report_last_ms = now;
  513. mavlink_obstacle_distance_t packet {};
  514. packet.time_usec = AP_HAL::micros64();
  515. packet.min_distance = 1;
  516. packet.max_distance = 0;
  517. packet.sensor_type = MAV_DISTANCE_SENSOR_LASER;
  518. packet.increment = 0; // use increment_f
  519. packet.angle_offset = 180;
  520. packet.increment_f = (-5); // NOTE! This is negative because the distances[] arc is counter-clockwise
  521. for (uint8_t i=0; i<MAVLINK_MSG_OBSTACLE_DISTANCE_FIELD_DISTANCES_LEN; i++) {
  522. // default distance unless overwritten
  523. packet.distances[i] = 65535;
  524. if (i >= scanner.points.length) {
  525. continue;
  526. }
  527. // convert m to cm and sanity check
  528. const Vector2f v = Vector2f(scanner.points.data[i].x, scanner.points.data[i].y);
  529. const float distance_cm = v.length()*100;
  530. if (distance_cm < packet.min_distance || distance_cm >= 65535) {
  531. continue;
  532. }
  533. packet.distances[i] = distance_cm;
  534. const float max_cm = scanner.ranges.data[i] * 100.0;
  535. if (packet.max_distance < max_cm && max_cm > 0 && max_cm < 65535) {
  536. packet.max_distance = max_cm;
  537. }
  538. }
  539. mavlink_message_t msg;
  540. mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
  541. uint8_t saved_seq = chan0_status->current_tx_seq;
  542. chan0_status->current_tx_seq = mavlink.seq;
  543. uint16_t len = mavlink_msg_obstacle_distance_encode(
  544. 0,
  545. 0,
  546. &msg, &packet);
  547. chan0_status->current_tx_seq = saved_seq;
  548. uint8_t msgbuf[len];
  549. len = mavlink_msg_to_send_buffer(msgbuf, &msg);
  550. if (len > 0) {
  551. mav_socket.send(msgbuf, len);
  552. }
  553. }
  554. }