APM:Libraries
SITL_cmdline.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
4 
5 #include "AP_HAL_SITL.h"
7 #include "HAL_SITL_Class.h"
8 #include "UARTDriver.h"
9 #include <stdio.h>
10 #include <signal.h>
11 #include <unistd.h>
13 
14 #include <SITL/SIM_Multicopter.h>
15 #include <SITL/SIM_Helicopter.h>
16 #include <SITL/SIM_SingleCopter.h>
17 #include <SITL/SIM_Plane.h>
18 #include <SITL/SIM_QuadPlane.h>
19 #include <SITL/SIM_Rover.h>
20 #include <SITL/SIM_CRRCSim.h>
21 #include <SITL/SIM_Gazebo.h>
22 #include <SITL/SIM_last_letter.h>
23 #include <SITL/SIM_JSBSim.h>
24 #include <SITL/SIM_Tracker.h>
25 #include <SITL/SIM_Balloon.h>
26 #include <SITL/SIM_FlightAxis.h>
27 #include <SITL/SIM_Calibration.h>
28 #include <SITL/SIM_XPlane.h>
29 #include <SITL/SIM_Submarine.h>
30 
31 extern const AP_HAL::HAL& hal;
32 
33 using namespace HALSITL;
34 using namespace SITL;
35 
36 // catch floating point exceptions
37 static void _sig_fpe(int signum)
38 {
39  fprintf(stderr, "ERROR: Floating point exception - aborting\n");
40  abort();
41 }
42 
44 {
45  printf("Options:\n"
46  "\t--help|-h display this help information\n"
47  "\t--wipe|-w wipe eeprom and dataflash\n"
48  "\t--unhide-groups|-u parameter enumeration ignores AP_PARAM_FLAG_ENABLE\n"
49  "\t--speedup|-s SPEEDUP set simulation speedup\n"
50  "\t--rate|-r RATE set SITL framerate\n"
51  "\t--console|-C use console instead of TCP ports\n"
52  "\t--instance|-I N set instance of SITL (adds 10*instance to all port numbers)\n"
53  // "\t--param|-P NAME=VALUE set some param\n" CURRENTLY BROKEN!
54  "\t--synthetic-clock|-S set synthetic clock mode\n"
55  "\t--home|-O HOME set home location (lat,lng,alt,yaw)\n"
56  "\t--model|-M MODEL set simulation model\n"
57  "\t--fdm|-F ADDRESS set FDM address, defaults to 127.0.0.1\n"
58  // "\t--client ADDRESS TCP address to connect uartC to\n" NOT USED
59  "\t--gimbal enable simulated MAVLink gimbal\n"
60  "\t--disable-fgview disable Flight Gear view\n"
61  "\t--autotest-dir DIR set directory for additional files\n"
62  "\t--defaults path set path to defaults file\n"
63  "\t--uartA device set device string for UARTA\n"
64  "\t--uartB device set device string for UARTB\n"
65  "\t--uartC device set device string for UARTC\n"
66  "\t--uartD device set device string for UARTD\n"
67  "\t--uartE device set device string for UARTE\n"
68  "\t--uartF device set device string for UARTE\n"
69  "\t--rtscts enable rtscts on serial ports (default false)\n"
70  "\t--base-port PORT set port num for base port(default 5670) must be before -I option\n"
71  "\t--rc-in-port PORT set port num for rc in\n"
72  "\t--rc-out-port PORT set port num for rc out\n"
73  "\t--sim-address ADDR set address string for simulator\n"
74  "\t--sim-port-in PORT set port num for simulator in\n"
75  "\t--sim-port-out PORT set port num for simulator out\n"
76  "\t--irlock-port PORT set port num for irlock\n"
77  );
78 }
79 
80 static const struct {
81  const char *name;
82  Aircraft *(*constructor)(const char *home_str, const char *frame_str);
83 } model_constructors[] = {
84  { "quadplane", QuadPlane::create },
85  { "xplane", XPlane::create },
86  { "firefly", QuadPlane::create },
87  { "+", MultiCopter::create },
88  { "quad", MultiCopter::create },
89  { "copter", MultiCopter::create },
90  { "x", MultiCopter::create },
91  { "hexa", MultiCopter::create },
92  { "octa", MultiCopter::create },
93  { "dodeca-hexa", MultiCopter::create },
94  { "tri", MultiCopter::create },
95  { "y6", MultiCopter::create },
96  { "heli", Helicopter::create },
97  { "heli-dual", Helicopter::create },
98  { "heli-compound", Helicopter::create },
99  { "singlecopter", SingleCopter::create },
100  { "coaxcopter", SingleCopter::create },
101  { "rover", SimRover::create },
102  { "crrcsim", CRRCSim::create },
103  { "jsbsim", JSBSim::create },
104  { "flightaxis", FlightAxis::create },
105  { "gazebo", Gazebo::create },
106  { "last_letter", last_letter::create },
107  { "tracker", Tracker::create },
108  { "balloon", Balloon::create },
109  { "plane", Plane::create },
110  { "calibration", Calibration::create },
111  { "vectored", Submarine::create },
112 };
113 
115 {
116  struct sigaction sa_fpe = {};
117 
118  sigemptyset(&sa_fpe.sa_mask);
119  sa_fpe.sa_handler = _sig_fpe;
120  sigaction(SIGFPE, &sa_fpe, nullptr);
121 
122  struct sigaction sa_pipe = {};
123 
124  sigemptyset(&sa_pipe.sa_mask);
125  sa_pipe.sa_handler = SIG_IGN; /* No-op SIGPIPE handler */
126  sigaction(SIGPIPE, &sa_pipe, nullptr);
127 }
128 
129 void SITL_State::_parse_command_line(int argc, char * const argv[])
130 {
131  int opt;
132  float speedup = 1.0f;
133  _instance = 0;
134  _synthetic_clock_mode = false;
135  // default to CMAC
136  const char *home_str = "-35.363261,149.165230,584,353";
137  const char *model_str = nullptr;
138  _client_address = nullptr;
139  _use_fg_view = true;
140  char *autotest_dir = nullptr;
141  _fdm_address = "127.0.0.1";
142 
143  const int BASE_PORT = 5760;
144  const int RCIN_PORT = 5501;
145  const int RCOUT_PORT = 5502;
146  const int FG_VIEW_PORT = 5503;
147  _base_port = BASE_PORT;
148  _rcin_port = RCIN_PORT;
149  _rcout_port = RCOUT_PORT;
150  _fg_view_port = FG_VIEW_PORT;
151 
152  const int SIM_IN_PORT = 9003;
153  const int SIM_OUT_PORT = 9002;
154  const int IRLOCK_PORT = 9005;
155  const char * _simulator_address = "127.0.0.1";
156  uint16_t _simulator_port_in = SIM_IN_PORT;
157  uint16_t _simulator_port_out = SIM_OUT_PORT;
158  _irlock_port = IRLOCK_PORT;
159 
160  enum long_options {
161  CMDLINE_CLIENT = 0,
162  CMDLINE_GIMBAL,
163  CMDLINE_FGVIEW,
164  CMDLINE_AUTOTESTDIR,
165  CMDLINE_DEFAULTS,
166  CMDLINE_UARTA,
167  CMDLINE_UARTB,
168  CMDLINE_UARTC,
169  CMDLINE_UARTD,
170  CMDLINE_UARTE,
171  CMDLINE_UARTF,
172  CMDLINE_RTSCTS,
173  CMDLINE_BASE_PORT,
174  CMDLINE_RCIN_PORT,
175  CMDLINE_RCOUT_PORT,
176  CMDLINE_SIM_ADDRESS,
177  CMDLINE_SIM_PORT_IN,
178  CMDLINE_SIM_PORT_OUT,
179  CMDLINE_IRLOCK_PORT,
180  };
181 
182  const struct GetOptLong::option options[] = {
183  {"help", false, 0, 'h'},
184  {"wipe", false, 0, 'w'},
185  {"unhide-groups", false, 0, 'u'},
186  {"speedup", true, 0, 's'},
187  {"rate", true, 0, 'r'},
188  {"console", false, 0, 'C'},
189  {"instance", true, 0, 'I'},
190  {"param", true, 0, 'P'},
191  {"synthetic-clock", false, 0, 'S'},
192  {"home", true, 0, 'O'},
193  {"model", true, 0, 'M'},
194  {"fdm", false, 0, 'F'},
195  {"client", true, 0, CMDLINE_CLIENT},
196  {"gimbal", false, 0, CMDLINE_GIMBAL},
197  {"disable-fgview", false, 0, CMDLINE_FGVIEW},
198  {"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
199  {"defaults", true, 0, CMDLINE_DEFAULTS},
200  {"uartA", true, 0, CMDLINE_UARTA},
201  {"uartB", true, 0, CMDLINE_UARTB},
202  {"uartC", true, 0, CMDLINE_UARTC},
203  {"uartD", true, 0, CMDLINE_UARTD},
204  {"uartE", true, 0, CMDLINE_UARTE},
205  {"uartF", true, 0, CMDLINE_UARTF},
206  {"rtscts", false, 0, CMDLINE_RTSCTS},
207  {"base-port", true, 0, CMDLINE_BASE_PORT},
208  {"rc-in-port", true, 0, CMDLINE_RCIN_PORT},
209  {"rc-out-port", true, 0, CMDLINE_RCOUT_PORT},
210  {"sim-address", true, 0, CMDLINE_SIM_ADDRESS},
211  {"sim-port-in", true, 0, CMDLINE_SIM_PORT_IN},
212  {"sim-port-out", true, 0, CMDLINE_SIM_PORT_OUT},
213  {"irlock-port", true, 0, CMDLINE_IRLOCK_PORT},
214  {0, false, 0, 0}
215  };
216 
217  if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) {
218  AP_HAL::panic("out of memory");
219  }
220  _set_signal_handlers();
221 
222  setvbuf(stdout, (char *)0, _IONBF, 0);
223  setvbuf(stderr, (char *)0, _IONBF, 0);
224 
225  GetOptLong gopt(argc, argv, "hwus:r:CI:P:SO:M:F:",
226  options);
227 
228  while ((opt = gopt.getoption()) != -1) {
229  switch (opt) {
230  case 'w':
232  unlink("dataflash.bin");
233  break;
234  case 'u':
236  break;
237  case 's':
238  speedup = strtof(gopt.optarg, nullptr);
239  break;
240  case 'r':
241  _framerate = (unsigned)atoi(gopt.optarg);
242  break;
243  case 'C':
245  break;
246  case 'I': {
247  _instance = atoi(gopt.optarg);
248  if (_base_port == BASE_PORT) {
249  _base_port += _instance * 10;
250  }
251  if (_rcout_port == RCOUT_PORT) {
252  _rcout_port += _instance * 10;
253  }
254  if (_rcin_port == RCIN_PORT) {
255  _rcin_port += _instance * 10;
256  }
257  if (_fg_view_port == FG_VIEW_PORT) {
258  _fg_view_port += _instance * 10;
259  }
260  if (_simulator_port_in == SIM_IN_PORT) {
261  _simulator_port_in += _instance * 10;
262  }
263  if (_simulator_port_out == SIM_OUT_PORT) {
264  _simulator_port_out += _instance * 10;
265  }
266  if (_irlock_port == IRLOCK_PORT) {
267  _irlock_port += _instance * 10;
268  }
269  }
270  break;
271  case 'P':
272  _set_param_default(gopt.optarg);
273  break;
274  case 'S':
275  _synthetic_clock_mode = true;
276  break;
277  case 'O':
278  home_str = gopt.optarg;
279  break;
280  case 'M':
281  model_str = gopt.optarg;
282  break;
283  case 'F':
284  _fdm_address = gopt.optarg;
285  break;
286  case CMDLINE_CLIENT:
287  _client_address = gopt.optarg;
288  break;
289  case CMDLINE_GIMBAL:
290  enable_gimbal = true;
291  break;
292  case CMDLINE_FGVIEW:
293  _use_fg_view = false;
294  break;
295  case CMDLINE_AUTOTESTDIR:
296  autotest_dir = strdup(gopt.optarg);
297  break;
298  case CMDLINE_DEFAULTS:
299  defaults_path = strdup(gopt.optarg);
300  break;
301  case CMDLINE_UARTA:
302  case CMDLINE_UARTB:
303  case CMDLINE_UARTC:
304  case CMDLINE_UARTD:
305  case CMDLINE_UARTE:
306  case CMDLINE_UARTF:
307  _uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
308  break;
309  case CMDLINE_RTSCTS:
310  _use_rtscts = true;
311  break;
312  case CMDLINE_BASE_PORT:
313  _base_port = atoi(gopt.optarg);
314  break;
315  case CMDLINE_RCIN_PORT:
316  _rcin_port = atoi(gopt.optarg);
317  break;
318  case CMDLINE_RCOUT_PORT:
319  _rcout_port = atoi(gopt.optarg);
320  break;
321  case CMDLINE_SIM_ADDRESS:
322  _simulator_address = gopt.optarg;
323  break;
324  case CMDLINE_SIM_PORT_IN:
325  _simulator_port_in = atoi(gopt.optarg);
326  break;
327  case CMDLINE_SIM_PORT_OUT:
328  _simulator_port_out = atoi(gopt.optarg);
329  break;
330  case CMDLINE_IRLOCK_PORT:
331  _irlock_port = atoi(gopt.optarg);
332  break;
333  default:
334  _usage();
335  exit(1);
336  }
337  }
338 
339  if (!model_str) {
340  printf("You must specify a vehicle model\n");
341  exit(1);
342  }
343 
344  for (uint8_t i=0; i < ARRAY_SIZE(model_constructors); i++) {
345  if (strncasecmp(model_constructors[i].name, model_str, strlen(model_constructors[i].name)) == 0) {
346  printf("Creating model %s at speed %.1f\n", model_str, speedup);
347  sitl_model = model_constructors[i].constructor(home_str, model_str);
348  sitl_model->set_interface_ports(_simulator_address, _simulator_port_in, _simulator_port_out);
349  sitl_model->set_speedup(speedup);
350  sitl_model->set_instance(_instance);
351  sitl_model->set_autotest_dir(autotest_dir);
352  _synthetic_clock_mode = true;
353  break;
354  }
355  }
356  if (sitl_model == nullptr) {
357  printf("Vehicle model (%s) not found\n", model_str);
358  exit(1);
359  }
360 
361  fprintf(stdout, "Starting sketch '%s'\n", SKETCH);
362 
363  if (strcmp(SKETCH, "ArduCopter") == 0) {
364  _vehicle = ArduCopter;
365  if (_framerate == 0) {
366  _framerate = 200;
367  }
368  } else if (strcmp(SKETCH, "APMrover2") == 0) {
369  _vehicle = APMrover2;
370  if (_framerate == 0) {
371  _framerate = 50;
372  }
373  // set right default throttle for rover (allowing for reverse)
374  pwm_input[2] = 1500;
375  } else if (strcmp(SKETCH, "ArduSub") == 0) {
376  _vehicle = ArduSub;
377  for(uint8_t i = 0; i < 8; i++) {
378  pwm_input[i] = 1500;
379  }
380  } else {
381  _vehicle = ArduPlane;
382  if (_framerate == 0) {
383  _framerate = 50;
384  }
385  }
386 
387  _sitl_setup(home_str);
388 }
389 
390 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
static void _sig_fpe(int signum)
void _parse_command_line(int argc, char *const argv[])
void _usage(void)
const char * name
static bool _console
Definition: UARTDriver.h:91
static const struct @110 model_constructors[]
const char * optarg
Definition: getopt_cpp.h:29
static void erase_all(void)
Definition: AP_Param.cpp:109
void _set_signal_handlers(void) const
int unlink(const char *pathname)
POSIX delete a file.
Definition: posix.c:1693
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
static void set_hide_disabled_groups(bool value)
Definition: AP_Param.h:410
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
int getoption(void)