APM:Libraries
SIM_JSBSim.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  simulator connector for ardupilot version of JSBSim
17 */
18 
19 #include "SIM_JSBSim.h"
20 
21 #include <arpa/inet.h>
22 #include <errno.h>
23 #include <fcntl.h>
24 #include <stdio.h>
25 #include <sys/stat.h>
26 #include <sys/types.h>
27 
28 #include <AP_HAL/AP_HAL.h>
29 
30 extern const AP_HAL::HAL& hal;
31 
32 namespace SITL {
33 
34 // the asprintf() calls are not worth checking for SITL
35 #pragma GCC diagnostic ignored "-Wunused-result"
36 
37 #define DEBUG_JSBSIM 1
38 
39 JSBSim::JSBSim(const char *home_str, const char *frame_str) :
40  Aircraft(home_str, frame_str),
41  sock_control(false),
42  sock_fgfdm(true),
43  initialised(false),
44  jsbsim_script(nullptr),
45  jsbsim_fgout(nullptr),
46  created_templates(false),
47  started_jsbsim(false),
48  opened_control_socket(false),
49  opened_fdm_socket(false),
50  frame(FRAME_NORMAL)
51 {
52  if (strstr(frame_str, "elevon")) {
54  } else if (strstr(frame_str, "vtail")) {
56  } else {
58  }
59  const char *model_name = strchr(frame_str, ':');
60  if (model_name != nullptr) {
61  jsbsim_model = model_name + 1;
62  }
63 }
64 
65 /*
66  create template files
67  */
69 {
70  if (created_templates) {
71  return true;
72  }
73  control_port = 5505 + instance*10;
74  fdm_port = 5504 + instance*10;
75 
76  asprintf(&jsbsim_script, "%s/jsbsim_start_%u.xml", autotest_dir, instance);
77  asprintf(&jsbsim_fgout, "%s/jsbsim_fgout_%u.xml", autotest_dir, instance);
78 
79  FILE *f = fopen(jsbsim_script, "w");
80  if (f == nullptr) {
81  AP_HAL::panic("Unable to create jsbsim script %s", jsbsim_script);
82  }
83  fprintf(f,
84 "<?xml version=\"1.0\" encoding=\"utf-8\"?>\n"
85 "<?xml-stylesheet type=\"text/xsl\" href=\"http://jsbsim.sf.net/JSBSimScript.xsl\"?>\n"
86 "<runscript xmlns:xsi=\"http://www.w3.org/2001/XMLSchema-instance\"\n"
87 " xsi:noNamespaceSchemaLocation=\"http://jsbsim.sf.net/JSBSimScript.xsd\"\n"
88 " name=\"Testing %s\">\n"
89 "\n"
90 " <description>\n"
91 " test ArduPlane using %s and JSBSim\n"
92 " </description>\n"
93 "\n"
94 " <use aircraft=\"%s\" initialize=\"reset\"/>\n"
95 "\n"
96 " <!-- we control the servos via the jsbsim console\n"
97 " interface on TCP 5124 -->\n"
98 " <input port=\"%u\"/>\n"
99 "\n"
100 " <run start=\"0\" end=\"10000000\" dt=\"0.001\">\n"
101 " <property value=\"0\"> simulation/notify-time-trigger </property>\n"
102 "\n"
103 " <event name=\"start engine\">\n"
104 " <condition> simulation/sim-time-sec le 0.01 </condition>\n"
105 " <set name=\"propulsion/engine[0]/set-running\" value=\"1\"/>\n"
106 " <notify/>\n"
107 " </event>\n"
108 "\n"
109 " <event name=\"Trim\">\n"
110 " <condition>simulation/sim-time-sec ge 0.01</condition>\n"
111 " <set name=\"simulation/do_simple_trim\" value=\"2\"/>\n"
112 " <notify/>\n"
113 " </event>\n"
114 " </run>\n"
115 "\n"
116 "</runscript>\n"
117 "",
118  jsbsim_model,
119  jsbsim_model,
120  jsbsim_model,
121  control_port);
122  fclose(f);
123 
124  f = fopen(jsbsim_fgout, "w");
125  if (f == nullptr) {
126  AP_HAL::panic("Unable to create jsbsim fgout script %s", jsbsim_fgout);
127  }
128  fprintf(f, "<?xml version=\"1.0\"?>\n"
129  "<output name=\"127.0.0.1\" type=\"FLIGHTGEAR\" port=\"%u\" protocol=\"udp\" rate=\"1000\"/>\n",
130  fdm_port);
131  fclose(f);
132 
133  char *jsbsim_reset;
134  asprintf(&jsbsim_reset, "%s/aircraft/%s/reset.xml", autotest_dir, jsbsim_model);
135  f = fopen(jsbsim_reset, "w");
136  if (f == nullptr) {
137  AP_HAL::panic("Unable to create jsbsim reset script %s", jsbsim_reset);
138  }
139  float r, p, y;
140  dcm.to_euler(&r, &p, &y);
141  fprintf(f,
142  "<?xml version=\"1.0\"?>\n"
143  "<initialize name=\"Start up location\">\n"
144  " <latitude unit=\"DEG\"> %f </latitude>\n"
145  " <longitude unit=\"DEG\"> %f </longitude>\n"
146  " <altitude unit=\"M\"> 1.3 </altitude>\n"
147  " <vt unit=\"FT/SEC\"> 0.0 </vt>\n"
148  " <gamma unit=\"DEG\"> 0.0 </gamma>\n"
149  " <phi unit=\"DEG\"> 0.0 </phi>\n"
150  " <theta unit=\"DEG\"> 13.0 </theta>\n"
151  " <psi unit=\"DEG\"> %f </psi>\n"
152  "</initialize>\n",
153  home.lat*1.0e-7,
154  home.lng*1.0e-7,
155  degrees(y));
156  fclose(f);
157 
158  created_templates = true;
159  return true;
160 }
161 
162 
163 /*
164  start JSBSim child
165  */
167 {
168  if (started_jsbsim) {
169  return true;
170  }
171  if (!open_fdm_socket()) {
172  return false;
173  }
174 
175  int p[2];
176  int devnull = open("/dev/null", O_RDWR|O_CLOEXEC);
177  if (pipe(p) != 0) {
178  AP_HAL::panic("Unable to create pipe");
179  }
180  pid_t child_pid = fork();
181  if (child_pid == 0) {
182  // in child
183  setsid();
184  dup2(devnull, 0);
185  dup2(p[1], 1);
186  close(p[0]);
187  for (uint8_t i=3; i<100; i++) {
188  close(i);
189  }
190  char *logdirective;
191  char *script;
192 
193  asprintf(&logdirective, "--logdirectivefile=%s", jsbsim_fgout);
194  asprintf(&script, "--script=%s", jsbsim_script);
195 
196  if (chdir(autotest_dir) != 0) {
198  exit(1);
199  }
200 
201  int ret = execlp("JSBSim",
202  "JSBSim",
203  "--realtime",
204  "--suspend",
205  "--nice",
206  "--simulation-rate=1000",
207  logdirective,
208  script,
209  nullptr);
210  if (ret != 0) {
211  perror("JSBSim");
212  }
213  exit(1);
214  }
215  close(p[1]);
216  jsbsim_stdout = p[0];
217 
218  // read startup to be sure it is running
219  char c;
220  if (read(jsbsim_stdout, &c, 1) != 1) {
221  AP_HAL::panic("Unable to start JSBSim");
222  }
223 
224  if (!expect("JSBSim Execution beginning")) {
225  AP_HAL::panic("Failed to start JSBSim");
226  }
227  if (!open_control_socket()) {
228  AP_HAL::panic("Failed to open JSBSim control socket");
229  }
230 
231  fcntl(jsbsim_stdout, F_SETFL, fcntl(jsbsim_stdout, F_GETFL, 0) | O_NONBLOCK);
232 
233  started_jsbsim = true;
234  check_stdout();
235  close(devnull);
236  return true;
237 }
238 
239 /*
240  check for stdout from JSBSim
241  */
243 {
244  char line[100];
245  ssize_t ret = ::read(jsbsim_stdout, line, sizeof(line));
246  if (ret > 0) {
247 #if DEBUG_JSBSIM
248  write(1, line, ret);
249 #endif
250  }
251 }
252 
253 /*
254  a simple function to wait for a string on jsbsim_stdout
255  */
256 bool JSBSim::expect(const char *str)
257 {
258  const char *basestr = str;
259  while (*str) {
260  char c;
261  if (read(jsbsim_stdout, &c, 1) != 1) {
262  return false;
263  }
264  if (c == *str) {
265  str++;
266  } else {
267  str = basestr;
268  }
269 #if DEBUG_JSBSIM
270  write(1, &c, 1);
271 #endif
272  }
273  return true;
274 }
275 
276 /*
277  open control socket to JSBSim
278  */
280 {
281  if (opened_control_socket) {
282  return true;
283  }
284  if (!sock_control.connect("127.0.0.1", control_port)) {
285  return false;
286  }
287  printf("Opened JSBSim control socket\n");
288  sock_control.set_blocking(false);
289  opened_control_socket = true;
290 
291  char startup[] =
292  "info\n"
293  "resume\n"
294  "step\n"
295  "set atmosphere/turb-type 4\n";
296  sock_control.send(startup, strlen(startup));
297  return true;
298 }
299 
300 /*
301  open fdm socket from JSBSim
302  */
304 {
305  if (opened_fdm_socket) {
306  return true;
307  }
308  if (!sock_fgfdm.bind("127.0.0.1", fdm_port)) {
309  check_stdout();
310  return false;
311  }
312  sock_fgfdm.set_blocking(false);
313  sock_fgfdm.reuseaddress();
314  opened_fdm_socket = true;
315  return true;
316 }
317 
318 
319 /*
320  decode and send servos
321 */
322 void JSBSim::send_servos(const struct sitl_input &input)
323 {
324  char *buf = nullptr;
325  float aileron = filtered_servo_angle(input, 0);
326  float elevator = filtered_servo_angle(input, 1);
327  float throttle = filtered_servo_range(input, 2);
328  float rudder = filtered_servo_angle(input, 3);
329  if (frame == FRAME_ELEVON) {
330  // fake an elevon plane
331  float ch1 = aileron;
332  float ch2 = elevator;
333  aileron = (ch2-ch1)/2.0f;
334  // the minus does away with the need for RC2_REV=-1
335  elevator = -(ch2+ch1)/2.0f;
336  } else if (frame == FRAME_VTAIL) {
337  // fake a vtail plane
338  float ch1 = elevator;
339  float ch2 = rudder;
340  // this matches VTAIL_OUTPUT==2
341  elevator = (ch2-ch1)/2.0f;
342  rudder = (ch2+ch1)/2.0f;
343  }
344  float wind_speed_fps = input.wind.speed / FEET_TO_METERS;
345  asprintf(&buf,
346  "set fcs/aileron-cmd-norm %f\n"
347  "set fcs/elevator-cmd-norm %f\n"
348  "set fcs/rudder-cmd-norm %f\n"
349  "set fcs/throttle-cmd-norm %f\n"
350  "set atmosphere/psiw-rad %f\n"
351  "set atmosphere/wind-mag-fps %f\n"
352  "set atmosphere/turbulence/milspec/windspeed_at_20ft_AGL-fps %f\n"
353  "set atmosphere/turbulence/milspec/severity %f\n"
354  "step\n",
355  aileron, elevator, rudder, throttle,
356  radians(input.wind.direction),
357  wind_speed_fps,
358  wind_speed_fps/3,
359  input.wind.turbulence);
360  ssize_t buflen = strlen(buf);
361  ssize_t sent = sock_control.send(buf, buflen);
362  free(buf);
363  if (sent < 0) {
364  if (errno != EAGAIN) {
365  fprintf(stderr, "Fatal: Failed to send on control socket: %s\n",
366  strerror(errno));
367  exit(1);
368  }
369  }
370  if (sent < buflen) {
371  fprintf(stderr, "Failed to send all bytes on control socket\n");
372  }
373 }
374 
375 /* nasty hack ....
376  JSBSim sends in little-endian
377  */
379 {
380  uint32_t *buf = (uint32_t *)this;
381  for (uint16_t i=0; i<sizeof(*this)/4; i++) {
382  buf[i] = ntohl(buf[i]);
383  }
384  // fixup the 3 doubles
385  buf = (uint32_t *)&longitude;
386  uint32_t tmp;
387  for (uint8_t i=0; i<3; i++) {
388  tmp = buf[0];
389  buf[0] = buf[1];
390  buf[1] = tmp;
391  buf += 2;
392  }
393 }
394 
395 /*
396  receive an update from the FDM
397  This is a blocking function
398  */
399 void JSBSim::recv_fdm(const struct sitl_input &input)
400 {
401  FGNetFDM fdm;
402  check_stdout();
403  while (sock_fgfdm.recv(&fdm, sizeof(fdm), 100) != sizeof(fdm)) {
404  send_servos(input);
405  check_stdout();
406  }
407  fdm.ByteSwap();
408 
410 
411  double p, q, r;
413  degrees(fdm.phidot), degrees(fdm.thetadot), degrees(fdm.psidot),
414  &p, &q, &r);
415  gyro = Vector3f(p, q, r);
416 
418  location.lat = degrees(fdm.latitude) * 1.0e7;
419  location.lng = degrees(fdm.longitude) * 1.0e7;
420  location.alt = fdm.agl*100 + home.alt;
421  dcm.from_euler(fdm.phi, fdm.theta, fdm.psi);
422  airspeed = fdm.vcas * FEET_TO_METERS;
424 
425  // update magnetic field
427 
428  rpm1 = fdm.rpm[0];
429  rpm2 = fdm.rpm[1];
430 
431  // assume 1kHz for now
432  time_now_us += 1000;
433 }
434 
436 {
437  const uint16_t buflen = 1024;
438  char buf[buflen];
439  ssize_t received;
440  do {
441  received = sock_control.recv(buf, buflen, 0);
442  if (received < 0) {
443  if (errno != EAGAIN && errno != EWOULDBLOCK) {
444  fprintf(stderr, "error recv on control socket: %s",
445  strerror(errno));
446  }
447  } else {
448  // fprintf(stderr, "received from control socket: %s\n", buf);
449  }
450  } while (received > 0);
451 }
452 /*
453  update the JSBSim simulation by one time step
454  */
455 void JSBSim::update(const struct sitl_input &input)
456 {
457  while (!initialised) {
458  if (!create_templates() ||
459  !start_JSBSim() ||
460  !open_control_socket() ||
461  !open_fdm_socket()) {
462  time_now_us = 1;
463  return;
464  }
465  initialised = true;
466  }
467  send_servos(input);
468  recv_fdm(input);
469  adjust_frame_time(1000);
470  sync_frame_time();
472 }
473 
474 } // namespace SITL
bool create_templates(void)
Definition: SIM_JSBSim.cpp:68
Vector3f accel_body
Definition: SIM_Aircraft.h:142
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
int printf(const char *fmt,...)
Definition: stdio.c:113
void sync_frame_time(void)
Vector3< float > Vector3f
Definition: vector3.h:246
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
int jsbsim_stdout
Definition: SIM_JSBSim.h:55
struct SITL::Aircraft::sitl_input::@201 wind
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
float rpm[FG_MAX_ENGINES]
Definition: SIM_JSBSim.h:139
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
bool opened_control_socket
Definition: SIM_JSBSim.h:62
float filtered_servo_range(const struct sitl_input &input, uint8_t idx)
uint8_t instance
Definition: SIM_Aircraft.h:170
SocketAPM sock_fgfdm
Definition: SIM_JSBSim.h:47
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
void recv_fdm(const struct sitl_input &input)
Definition: SIM_JSBSim.cpp:399
bool created_templates
Definition: SIM_JSBSim.h:60
double latitude
Definition: SIM_JSBSim.h:100
Location location
Definition: SIM_Aircraft.h:127
bool start_JSBSim(void)
Definition: SIM_JSBSim.cpp:166
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
double longitude
Definition: SIM_JSBSim.h:99
uint16_t fdm_port
Definition: SIM_JSBSim.h:52
char * jsbsim_script
Definition: SIM_JSBSim.h:53
static void convert_body_frame(double rollDeg, double pitchDeg, double rollRate, double pitchRate, double yawRate, double *p, double *q, double *r)
Definition: SITL.cpp:182
void send_servos(const struct sitl_input &input)
Definition: SIM_JSBSim.cpp:322
void update(const struct sitl_input &input)
Definition: SIM_JSBSim.cpp:455
void perror(const char *s)
POSIX perror() - convert POSIX errno to text with user message.
Definition: posix.c:1827
float airspeed_pitot
Definition: SIM_Aircraft.h:144
void check_stdout(void)
Definition: SIM_JSBSim.cpp:242
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
#define f(i)
const char * autotest_dir
Definition: SIM_Aircraft.h:171
bool opened_fdm_socket
Definition: SIM_JSBSim.h:63
Vector3f velocity_ef
Definition: SIM_Aircraft.h:136
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
uint64_t time_now_us
Definition: SIM_Aircraft.h:160
bool open_fdm_socket(void)
Definition: SIM_JSBSim.cpp:303
char * jsbsim_fgout
Definition: SIM_JSBSim.h:54
void drain_control_socket()
Definition: SIM_JSBSim.cpp:435
const char * jsbsim_model
Definition: SIM_JSBSim.h:58
JSBSim(const char *home_str, const char *frame_str)
Definition: SIM_JSBSim.cpp:39
bool expect(const char *str)
Definition: SIM_JSBSim.cpp:256
void adjust_frame_time(float rate)
static uint8_t buflen
Definition: srxl.cpp:57
void free(void *ptr)
Definition: malloc.c:81
void update_mag_field_bf(void)
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
void ByteSwap(void)
Definition: SIM_JSBSim.cpp:378
FILE * fopen(const char *path, const char *mode)
POSIX Open a file with path name and ascii file mode string.
Definition: posix.c:772
int chdir(const char *pathname)
POSIX change directory.
Definition: posix.c:1489
static constexpr float radians(float deg)
Definition: AP_Math.h:158
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
bool open_control_socket(void)
Definition: SIM_JSBSim.cpp:279
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
bool started_jsbsim
Definition: SIM_JSBSim.h:61
SocketAPM sock_control
Definition: SIM_JSBSim.h:44
uint16_t control_port
Definition: SIM_JSBSim.h:51
#define degrees(x)
Definition: moduletest.c:23
const float FEET_TO_METERS
Definition: SIM_Aircraft.h:191
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool initialised
Definition: SIM_JSBSim.h:49
float filtered_servo_angle(const struct sitl_input &input, uint8_t idx)
enum SITL::JSBSim::@206 frame