SIM_JSBSim.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483
  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 JSBSim
  15. */
  16. #include "SIM_JSBSim.h"
  17. #include <arpa/inet.h>
  18. #include <errno.h>
  19. #include <fcntl.h>
  20. #include <stdio.h>
  21. #include <sys/stat.h>
  22. #include <sys/types.h>
  23. #include <AP_HAL/AP_HAL.h>
  24. extern const AP_HAL::HAL& hal;
  25. namespace SITL {
  26. // the asprintf() calls are not worth checking for SITL
  27. #pragma GCC diagnostic ignored "-Wunused-result"
  28. #define DEBUG_JSBSIM 1
  29. JSBSim::JSBSim(const char *frame_str) :
  30. Aircraft(frame_str),
  31. sock_control(false),
  32. sock_fgfdm(true),
  33. initialised(false),
  34. jsbsim_script(nullptr),
  35. jsbsim_fgout(nullptr),
  36. created_templates(false),
  37. started_jsbsim(false),
  38. opened_control_socket(false),
  39. opened_fdm_socket(false),
  40. frame(FRAME_NORMAL)
  41. {
  42. if (strstr(frame_str, "elevon")) {
  43. frame = FRAME_ELEVON;
  44. } else if (strstr(frame_str, "vtail")) {
  45. frame = FRAME_VTAIL;
  46. } else {
  47. frame = FRAME_NORMAL;
  48. }
  49. const char *model_name = strchr(frame_str, ':');
  50. if (model_name != nullptr) {
  51. jsbsim_model = model_name + 1;
  52. }
  53. control_port = 5505 + instance*10;
  54. fdm_port = 5504 + instance*10;
  55. printf("JSBSim backend started: control_port=%u fdm_port=%u\n",
  56. control_port, fdm_port);
  57. }
  58. /*
  59. create template files
  60. */
  61. bool JSBSim::create_templates(void)
  62. {
  63. if (created_templates) {
  64. return true;
  65. }
  66. asprintf(&jsbsim_script, "%s/jsbsim_start_%u.xml", autotest_dir, instance);
  67. asprintf(&jsbsim_fgout, "%s/jsbsim_fgout_%u.xml", autotest_dir, instance);
  68. printf("JSBSim_script: '%s'\n", jsbsim_script);
  69. printf("JSBSim_fgout: '%s'\n", jsbsim_fgout);
  70. FILE *f = fopen(jsbsim_script, "w");
  71. if (f == nullptr) {
  72. AP_HAL::panic("Unable to create jsbsim script %s", jsbsim_script);
  73. }
  74. fprintf(f,
  75. "<?xml version=\"1.0\" encoding=\"utf-8\"?>\n"
  76. "<?xml-stylesheet type=\"text/xsl\" href=\"http://jsbsim.sf.net/JSBSimScript.xsl\"?>\n"
  77. "<runscript xmlns:xsi=\"http://www.w3.org/2001/XMLSchema-instance\"\n"
  78. " xsi:noNamespaceSchemaLocation=\"http://jsbsim.sf.net/JSBSimScript.xsd\"\n"
  79. " name=\"Testing %s\">\n"
  80. "\n"
  81. " <description>\n"
  82. " test ArduPlane using %s and JSBSim\n"
  83. " </description>\n"
  84. "\n"
  85. " <use aircraft=\"%s\" initialize=\"reset\"/>\n"
  86. "\n"
  87. " <!-- we control the servos via the jsbsim console\n"
  88. " interface on TCP 5124 -->\n"
  89. " <input port=\"%u\"/>\n"
  90. "\n"
  91. " <run start=\"0\" end=\"10000000\" dt=\"%.6f\">\n"
  92. " <property value=\"0\"> simulation/notify-time-trigger </property>\n"
  93. "\n"
  94. " <event name=\"start engine\">\n"
  95. " <condition> simulation/sim-time-sec le 0.01 </condition>\n"
  96. " <set name=\"propulsion/engine[0]/set-running\" value=\"1\"/>\n"
  97. " <notify/>\n"
  98. " </event>\n"
  99. "\n"
  100. " <event name=\"Trim\">\n"
  101. " <condition>simulation/sim-time-sec ge 0.01</condition>\n"
  102. " <set name=\"simulation/do_simple_trim\" value=\"2\"/>\n"
  103. " <notify/>\n"
  104. " </event>\n"
  105. " </run>\n"
  106. "\n"
  107. "</runscript>\n"
  108. "",
  109. jsbsim_model,
  110. jsbsim_model,
  111. jsbsim_model,
  112. control_port,
  113. 1.0/rate_hz);
  114. fclose(f);
  115. f = fopen(jsbsim_fgout, "w");
  116. if (f == nullptr) {
  117. AP_HAL::panic("Unable to create jsbsim fgout script %s", jsbsim_fgout);
  118. }
  119. fprintf(f, "<?xml version=\"1.0\"?>\n"
  120. "<output name=\"127.0.0.1\" type=\"FLIGHTGEAR\" port=\"%u\" protocol=\"UDP\" rate=\"%f\">\n"
  121. " <time type=\"simulation\" resolution=\"1e-6\"/>\n"
  122. "</output>",
  123. fdm_port, rate_hz);
  124. fclose(f);
  125. char *jsbsim_reset;
  126. asprintf(&jsbsim_reset, "%s/aircraft/%s/reset.xml", autotest_dir, jsbsim_model);
  127. printf("JSBSim_reset: '%s'\n", jsbsim_reset);
  128. f = fopen(jsbsim_reset, "w");
  129. if (f == nullptr) {
  130. AP_HAL::panic("Unable to create jsbsim reset script %s", jsbsim_reset);
  131. }
  132. float r, p, y;
  133. dcm.to_euler(&r, &p, &y);
  134. fprintf(f,
  135. "<?xml version=\"1.0\"?>\n"
  136. "<initialize name=\"Start up location\">\n"
  137. " <latitude unit=\"DEG\" type=\"geodetic\"> %f </latitude>\n"
  138. " <longitude unit=\"DEG\"> %f </longitude>\n"
  139. " <altitude unit=\"M\"> 1.3 </altitude>\n"
  140. " <vt unit=\"FT/SEC\"> 0.0 </vt>\n"
  141. " <gamma unit=\"DEG\"> 0.0 </gamma>\n"
  142. " <phi unit=\"DEG\"> 0.0 </phi>\n"
  143. " <theta unit=\"DEG\"> 13.0 </theta>\n"
  144. " <psi unit=\"DEG\"> %f </psi>\n"
  145. "</initialize>\n",
  146. home.lat*1.0e-7,
  147. home.lng*1.0e-7,
  148. degrees(y));
  149. fclose(f);
  150. created_templates = true;
  151. return true;
  152. }
  153. /*
  154. start JSBSim child
  155. */
  156. bool JSBSim::start_JSBSim(void)
  157. {
  158. if (started_jsbsim) {
  159. return true;
  160. }
  161. if (!open_fdm_socket()) {
  162. return false;
  163. }
  164. int p[2];
  165. int devnull = open("/dev/null", O_RDWR|O_CLOEXEC);
  166. if (pipe(p) != 0) {
  167. AP_HAL::panic("Unable to create pipe");
  168. }
  169. pid_t child_pid = fork();
  170. if (child_pid == 0) {
  171. // in child
  172. setsid();
  173. dup2(devnull, 0);
  174. dup2(p[1], 1);
  175. close(p[0]);
  176. for (uint8_t i=3; i<100; i++) {
  177. close(i);
  178. }
  179. char *logdirective;
  180. char *script;
  181. char *nice;
  182. char *rate;
  183. asprintf(&logdirective, "--logdirectivefile=%s", jsbsim_fgout);
  184. asprintf(&script, "--script=%s", jsbsim_script);
  185. asprintf(&nice, "--nice=%.8f", 10*1e-9);
  186. asprintf(&rate, "--simulation-rate=%f", rate_hz);
  187. if (chdir(autotest_dir) != 0) {
  188. perror(autotest_dir);
  189. exit(1);
  190. }
  191. int ret = execlp("JSBSim",
  192. "JSBSim",
  193. "--suspend",
  194. rate,
  195. nice,
  196. logdirective,
  197. script,
  198. nullptr);
  199. if (ret != 0) {
  200. perror("JSBSim");
  201. }
  202. exit(1);
  203. }
  204. close(p[1]);
  205. jsbsim_stdout = p[0];
  206. // read startup to be sure it is running
  207. char c;
  208. if (read(jsbsim_stdout, &c, 1) != 1) {
  209. AP_HAL::panic("Unable to start JSBSim");
  210. }
  211. if (!expect("JSBSim Execution beginning")) {
  212. AP_HAL::panic("Failed to start JSBSim");
  213. }
  214. if (!open_control_socket()) {
  215. AP_HAL::panic("Failed to open JSBSim control socket");
  216. }
  217. fcntl(jsbsim_stdout, F_SETFL, fcntl(jsbsim_stdout, F_GETFL, 0) | O_NONBLOCK);
  218. started_jsbsim = true;
  219. check_stdout();
  220. close(devnull);
  221. return true;
  222. }
  223. /*
  224. check for stdout from JSBSim
  225. */
  226. void JSBSim::check_stdout(void)
  227. {
  228. char line[100];
  229. ssize_t ret = ::read(jsbsim_stdout, line, sizeof(line));
  230. if (ret > 0) {
  231. #if DEBUG_JSBSIM
  232. write(1, line, ret);
  233. #endif
  234. }
  235. }
  236. /*
  237. a simple function to wait for a string on jsbsim_stdout
  238. */
  239. bool JSBSim::expect(const char *str)
  240. {
  241. const char *basestr = str;
  242. while (*str) {
  243. char c;
  244. if (read(jsbsim_stdout, &c, 1) != 1) {
  245. return false;
  246. }
  247. if (c == *str) {
  248. str++;
  249. } else {
  250. str = basestr;
  251. }
  252. #if DEBUG_JSBSIM
  253. write(1, &c, 1);
  254. #endif
  255. }
  256. return true;
  257. }
  258. /*
  259. open control socket to JSBSim
  260. */
  261. bool JSBSim::open_control_socket(void)
  262. {
  263. if (opened_control_socket) {
  264. return true;
  265. }
  266. if (!sock_control.connect("127.0.0.1", control_port)) {
  267. return false;
  268. }
  269. printf("Opened JSBSim control socket\n");
  270. sock_control.set_blocking(false);
  271. opened_control_socket = true;
  272. char startup[] =
  273. "info\n"
  274. "resume\n"
  275. "iterate 1\n"
  276. "set atmosphere/turb-type 4\n";
  277. sock_control.send(startup, strlen(startup));
  278. return true;
  279. }
  280. /*
  281. open fdm socket from JSBSim
  282. */
  283. bool JSBSim::open_fdm_socket(void)
  284. {
  285. if (opened_fdm_socket) {
  286. return true;
  287. }
  288. if (!sock_fgfdm.bind("127.0.0.1", fdm_port)) {
  289. check_stdout();
  290. return false;
  291. }
  292. sock_fgfdm.set_blocking(false);
  293. sock_fgfdm.reuseaddress();
  294. opened_fdm_socket = true;
  295. return true;
  296. }
  297. /*
  298. decode and send servos
  299. */
  300. void JSBSim::send_servos(const struct sitl_input &input)
  301. {
  302. char *buf = nullptr;
  303. float aileron = filtered_servo_angle(input, 0);
  304. float elevator = filtered_servo_angle(input, 1);
  305. float throttle = filtered_servo_range(input, 2);
  306. float rudder = filtered_servo_angle(input, 3);
  307. if (frame == FRAME_ELEVON) {
  308. // fake an elevon plane
  309. float ch1 = aileron;
  310. float ch2 = elevator;
  311. aileron = (ch2-ch1)/2.0f;
  312. // the minus does away with the need for RC2_REVERSED=-1
  313. elevator = -(ch2+ch1)/2.0f;
  314. } else if (frame == FRAME_VTAIL) {
  315. // fake a vtail plane
  316. float ch1 = elevator;
  317. float ch2 = rudder;
  318. // this matches VTAIL_OUTPUT==2
  319. elevator = (ch2-ch1)/2.0f;
  320. rudder = (ch2+ch1)/2.0f;
  321. }
  322. float wind_speed_fps = input.wind.speed / FEET_TO_METERS;
  323. asprintf(&buf,
  324. "set fcs/aileron-cmd-norm %f\n"
  325. "set fcs/elevator-cmd-norm %f\n"
  326. "set fcs/rudder-cmd-norm %f\n"
  327. "set fcs/throttle-cmd-norm %f\n"
  328. "set atmosphere/psiw-rad %f\n"
  329. "set atmosphere/wind-mag-fps %f\n"
  330. "set atmosphere/turbulence/milspec/windspeed_at_20ft_AGL-fps %f\n"
  331. "set atmosphere/turbulence/milspec/severity %f\n"
  332. "iterate 1\n",
  333. aileron, elevator, rudder, throttle,
  334. radians(input.wind.direction),
  335. wind_speed_fps,
  336. wind_speed_fps/3,
  337. input.wind.turbulence);
  338. ssize_t buflen = strlen(buf);
  339. ssize_t sent = sock_control.send(buf, buflen);
  340. free(buf);
  341. if (sent < 0) {
  342. if (errno != EAGAIN) {
  343. fprintf(stderr, "Fatal: Failed to send on control socket: %s\n",
  344. strerror(errno));
  345. exit(1);
  346. }
  347. }
  348. if (sent < buflen) {
  349. fprintf(stderr, "Failed to send all bytes on control socket\n");
  350. }
  351. }
  352. /* nasty hack ....
  353. JSBSim sends in little-endian
  354. */
  355. void FGNetFDM::ByteSwap(void)
  356. {
  357. uint32_t *buf = (uint32_t *)this;
  358. for (uint16_t i=0; i<sizeof(*this)/4; i++) {
  359. buf[i] = ntohl(buf[i]);
  360. }
  361. // fixup the 3 doubles
  362. buf = (uint32_t *)&longitude;
  363. uint32_t tmp;
  364. for (uint8_t i=0; i<3; i++) {
  365. tmp = buf[0];
  366. buf[0] = buf[1];
  367. buf[1] = tmp;
  368. buf += 2;
  369. }
  370. }
  371. /*
  372. receive an update from the FDM
  373. This is a blocking function
  374. */
  375. void JSBSim::recv_fdm(const struct sitl_input &input)
  376. {
  377. FGNetFDM fdm;
  378. check_stdout();
  379. do {
  380. while (sock_fgfdm.recv(&fdm, sizeof(fdm), 100) != sizeof(fdm)) {
  381. send_servos(input);
  382. check_stdout();
  383. }
  384. fdm.ByteSwap();
  385. } while (fdm.cur_time == time_now_us);
  386. accel_body = Vector3f(fdm.A_X_pilot, fdm.A_Y_pilot, fdm.A_Z_pilot) * FEET_TO_METERS;
  387. double p, q, r;
  388. SITL::convert_body_frame(degrees(fdm.phi), degrees(fdm.theta),
  389. degrees(fdm.phidot), degrees(fdm.thetadot), degrees(fdm.psidot),
  390. &p, &q, &r);
  391. gyro = Vector3f(p, q, r);
  392. velocity_ef = Vector3f(fdm.v_north, fdm.v_east, fdm.v_down) * FEET_TO_METERS;
  393. location.lat = degrees(fdm.latitude) * 1.0e7;
  394. location.lng = degrees(fdm.longitude) * 1.0e7;
  395. location.alt = fdm.agl*100 + home.alt;
  396. dcm.from_euler(fdm.phi, fdm.theta, fdm.psi);
  397. airspeed = fdm.vcas * KNOTS_TO_METERS_PER_SECOND;
  398. airspeed_pitot = airspeed;
  399. // update magnetic field
  400. update_mag_field_bf();
  401. rpm1 = fdm.rpm[0];
  402. rpm2 = fdm.rpm[1];
  403. time_now_us = fdm.cur_time;
  404. }
  405. void JSBSim::drain_control_socket()
  406. {
  407. const uint16_t buflen = 1024;
  408. char buf[buflen];
  409. ssize_t received;
  410. do {
  411. received = sock_control.recv(buf, buflen, 0);
  412. } while (received > 0);
  413. }
  414. /*
  415. update the JSBSim simulation by one time step
  416. */
  417. void JSBSim::update(const struct sitl_input &input)
  418. {
  419. while (!initialised) {
  420. if (!create_templates() ||
  421. !start_JSBSim() ||
  422. !open_control_socket() ||
  423. !open_fdm_socket()) {
  424. time_now_us = 1;
  425. return;
  426. }
  427. initialised = true;
  428. }
  429. send_servos(input);
  430. recv_fdm(input);
  431. adjust_frame_time(rate_hz);
  432. sync_frame_time();
  433. drain_control_socket();
  434. }
  435. } // namespace SITL