SITL_cmdline.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488
  1. #include <AP_HAL/AP_HAL.h>
  2. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  3. #include "AP_HAL_SITL.h"
  4. #include "AP_HAL_SITL_Namespace.h"
  5. #include "HAL_SITL_Class.h"
  6. #include "UARTDriver.h"
  7. #include <AP_HAL/utility/getopt_cpp.h>
  8. #include <AP_Logger/AP_Logger_SITL.h>
  9. #include <SITL/SIM_Multicopter.h>
  10. #include <SITL/SIM_Helicopter.h>
  11. #include <SITL/SIM_SingleCopter.h>
  12. #include <SITL/SIM_Plane.h>
  13. #include <SITL/SIM_QuadPlane.h>
  14. #include <SITL/SIM_Rover.h>
  15. #include <SITL/SIM_BalanceBot.h>
  16. #include <SITL/SIM_Sailboat.h>
  17. #include <SITL/SIM_CRRCSim.h>
  18. #include <SITL/SIM_Gazebo.h>
  19. #include <SITL/SIM_last_letter.h>
  20. #include <SITL/SIM_JSBSim.h>
  21. #include <SITL/SIM_Tracker.h>
  22. #include <SITL/SIM_Balloon.h>
  23. #include <SITL/SIM_FlightAxis.h>
  24. #include <SITL/SIM_Calibration.h>
  25. #include <SITL/SIM_XPlane.h>
  26. #include <SITL/SIM_Submarine.h>
  27. #include <SITL/SIM_SilentWings.h>
  28. #include <SITL/SIM_Morse.h>
  29. #include <SITL/SIM_AirSim.h>
  30. #include <SITL/SIM_Scrimmage.h>
  31. #include <SITL/SIM_Webots.h>
  32. #include <signal.h>
  33. #include <stdio.h>
  34. extern const AP_HAL::HAL& hal;
  35. using namespace HALSITL;
  36. using namespace SITL;
  37. // catch floating point exceptions
  38. static void _sig_fpe(int signum)
  39. {
  40. fprintf(stderr, "ERROR: Floating point exception - aborting\n");
  41. AP_HAL::dump_stack_trace();
  42. abort();
  43. }
  44. // catch segfault
  45. static void _sig_segv(int signum)
  46. {
  47. fprintf(stderr, "ERROR: segmentation fault - aborting\n");
  48. AP_HAL::dump_stack_trace();
  49. abort();
  50. }
  51. void SITL_State::_usage(void)
  52. {
  53. printf("Options:\n"
  54. "\t--help|-h display this help information\n"
  55. "\t--wipe|-w wipe eeprom\n"
  56. "\t--unhide-groups|-u parameter enumeration ignores AP_PARAM_FLAG_ENABLE\n"
  57. "\t--speedup|-s SPEEDUP set simulation speedup\n"
  58. "\t--rate|-r RATE set SITL framerate\n"
  59. "\t--console|-C use console instead of TCP ports\n"
  60. "\t--instance|-I N set instance of SITL (adds 10*instance to all port numbers)\n"
  61. // "\t--param|-P NAME=VALUE set some param\n" CURRENTLY BROKEN!
  62. "\t--synthetic-clock|-S set synthetic clock mode\n"
  63. "\t--home|-O HOME set start location (lat,lng,alt,yaw)\n"
  64. "\t--model|-M MODEL set simulation model\n"
  65. "\t--config string set additional simulation config string\n"
  66. "\t--fg|-F ADDRESS set Flight Gear view address, defaults to 127.0.0.1\n"
  67. "\t--disable-fgview disable Flight Gear view\n"
  68. "\t--gimbal enable simulated MAVLink gimbal\n"
  69. "\t--autotest-dir DIR set directory for additional files\n"
  70. "\t--defaults path set path to defaults file\n"
  71. "\t--uartA device set device string for UARTA\n"
  72. "\t--uartB device set device string for UARTB\n"
  73. "\t--uartC device set device string for UARTC\n"
  74. "\t--uartD device set device string for UARTD\n"
  75. "\t--uartE device set device string for UARTE\n"
  76. "\t--uartF device set device string for UARTF\n"
  77. "\t--uartG device set device string for UARTG\n"
  78. "\t--uartH device set device string for UARTH\n"
  79. "\t--rtscts enable rtscts on serial ports (default false)\n"
  80. "\t--base-port PORT set port num for base port(default 5670) must be before -I option\n"
  81. "\t--rc-in-port PORT set port num for rc in\n"
  82. "\t--sim-address ADDR set address string for simulator\n"
  83. "\t--sim-port-in PORT set port num for simulator in\n"
  84. "\t--sim-port-out PORT set port num for simulator out\n"
  85. "\t--irlock-port PORT set port num for irlock\n"
  86. );
  87. }
  88. static const struct {
  89. const char *name;
  90. Aircraft *(*constructor)(const char *frame_str);
  91. } model_constructors[] = {
  92. { "quadplane", QuadPlane::create },
  93. { "xplane", XPlane::create },
  94. { "firefly", QuadPlane::create },
  95. { "+", MultiCopter::create },
  96. { "quad", MultiCopter::create },
  97. { "copter", MultiCopter::create },
  98. { "x", MultiCopter::create },
  99. { "bfx", MultiCopter::create },
  100. { "djix", MultiCopter::create },
  101. { "cwx", MultiCopter::create },
  102. { "hexa", MultiCopter::create },
  103. { "octa", MultiCopter::create },
  104. { "dodeca-hexa", MultiCopter::create },
  105. { "tri", MultiCopter::create },
  106. { "y6", MultiCopter::create },
  107. { "heli", Helicopter::create },
  108. { "heli-dual", Helicopter::create },
  109. { "heli-compound", Helicopter::create },
  110. { "singlecopter", SingleCopter::create },
  111. { "coaxcopter", SingleCopter::create },
  112. { "rover", SimRover::create },
  113. { "balancebot", BalanceBot::create },
  114. { "sailboat", Sailboat::create },
  115. { "crrcsim", CRRCSim::create },
  116. { "jsbsim", JSBSim::create },
  117. { "flightaxis", FlightAxis::create },
  118. { "gazebo", Gazebo::create },
  119. { "last_letter", last_letter::create },
  120. { "tracker", Tracker::create },
  121. { "balloon", Balloon::create },
  122. { "plane", Plane::create },
  123. { "calibration", Calibration::create },
  124. { "vectored", Submarine::create },
  125. { "silentwings", SilentWings::create },
  126. { "vectored_6dof", Submarine::create },
  127. { "morse", Morse::create },
  128. { "airsim", AirSim::create},
  129. { "scrimmage", Scrimmage::create },
  130. { "webots", Webots::create },
  131. };
  132. void SITL_State::_set_signal_handlers(void) const
  133. {
  134. struct sigaction sa_fpe = {};
  135. sigemptyset(&sa_fpe.sa_mask);
  136. sa_fpe.sa_handler = _sig_fpe;
  137. sigaction(SIGFPE, &sa_fpe, nullptr);
  138. struct sigaction sa_pipe = {};
  139. sigemptyset(&sa_pipe.sa_mask);
  140. sa_pipe.sa_handler = SIG_IGN; /* No-op SIGPIPE handler */
  141. sigaction(SIGPIPE, &sa_pipe, nullptr);
  142. struct sigaction sa_segv = {};
  143. sigemptyset(&sa_segv.sa_mask);
  144. sa_segv.sa_handler = _sig_segv;
  145. sigaction(SIGSEGV, &sa_segv, nullptr);
  146. }
  147. void SITL_State::_parse_command_line(int argc, char * const argv[])
  148. {
  149. int opt;
  150. float speedup = 1.0f;
  151. _instance = 0;
  152. _synthetic_clock_mode = false;
  153. // default to CMAC
  154. const char *home_str = nullptr;
  155. const char *model_str = nullptr;
  156. _use_fg_view = true;
  157. char *autotest_dir = nullptr;
  158. _fg_address = "127.0.0.1";
  159. const char* config = "";
  160. const int BASE_PORT = 5760;
  161. const int RCIN_PORT = 5501;
  162. const int FG_VIEW_PORT = 5503;
  163. _base_port = BASE_PORT;
  164. _rcin_port = RCIN_PORT;
  165. _fg_view_port = FG_VIEW_PORT;
  166. const int SIM_IN_PORT = 9003;
  167. const int SIM_OUT_PORT = 9002;
  168. const int IRLOCK_PORT = 9005;
  169. const char * simulator_address = "127.0.0.1";
  170. uint16_t simulator_port_in = SIM_IN_PORT;
  171. uint16_t simulator_port_out = SIM_OUT_PORT;
  172. _irlock_port = IRLOCK_PORT;
  173. enum long_options {
  174. CMDLINE_GIMBAL = 1,
  175. CMDLINE_FGVIEW,
  176. CMDLINE_AUTOTESTDIR,
  177. CMDLINE_DEFAULTS,
  178. CMDLINE_UARTA,
  179. CMDLINE_UARTB,
  180. CMDLINE_UARTC,
  181. CMDLINE_UARTD,
  182. CMDLINE_UARTE,
  183. CMDLINE_UARTF,
  184. CMDLINE_UARTG,
  185. CMDLINE_UARTH,
  186. CMDLINE_RTSCTS,
  187. CMDLINE_BASE_PORT,
  188. CMDLINE_RCIN_PORT,
  189. CMDLINE_SIM_ADDRESS,
  190. CMDLINE_SIM_PORT_IN,
  191. CMDLINE_SIM_PORT_OUT,
  192. CMDLINE_IRLOCK_PORT,
  193. };
  194. const struct GetOptLong::option options[] = {
  195. {"help", false, 0, 'h'},
  196. {"wipe", false, 0, 'w'},
  197. {"unhide-groups", false, 0, 'u'},
  198. {"speedup", true, 0, 's'},
  199. {"rate", true, 0, 'r'},
  200. {"console", false, 0, 'C'},
  201. {"instance", true, 0, 'I'},
  202. {"param", true, 0, 'P'},
  203. {"synthetic-clock", false, 0, 'S'},
  204. {"home", true, 0, 'O'},
  205. {"model", true, 0, 'M'},
  206. {"config", true, 0, 'c'},
  207. {"fg", true, 0, 'F'},
  208. {"gimbal", false, 0, CMDLINE_GIMBAL},
  209. {"disable-fgview", false, 0, CMDLINE_FGVIEW},
  210. {"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
  211. {"defaults", true, 0, CMDLINE_DEFAULTS},
  212. {"uartA", true, 0, CMDLINE_UARTA},
  213. {"uartB", true, 0, CMDLINE_UARTB},
  214. {"uartC", true, 0, CMDLINE_UARTC},
  215. {"uartD", true, 0, CMDLINE_UARTD},
  216. {"uartE", true, 0, CMDLINE_UARTE},
  217. {"uartF", true, 0, CMDLINE_UARTF},
  218. {"uartG", true, 0, CMDLINE_UARTG},
  219. {"uartH", true, 0, CMDLINE_UARTH},
  220. {"rtscts", false, 0, CMDLINE_RTSCTS},
  221. {"base-port", true, 0, CMDLINE_BASE_PORT},
  222. {"rc-in-port", true, 0, CMDLINE_RCIN_PORT},
  223. {"sim-address", true, 0, CMDLINE_SIM_ADDRESS},
  224. {"sim-port-in", true, 0, CMDLINE_SIM_PORT_IN},
  225. {"sim-port-out", true, 0, CMDLINE_SIM_PORT_OUT},
  226. {"irlock-port", true, 0, CMDLINE_IRLOCK_PORT},
  227. {0, false, 0, 0}
  228. };
  229. if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) {
  230. AP_HAL::panic("out of memory");
  231. }
  232. _set_signal_handlers();
  233. setvbuf(stdout, (char *)0, _IONBF, 0);
  234. setvbuf(stderr, (char *)0, _IONBF, 0);
  235. GetOptLong gopt(argc, argv, "hwus:r:CI:P:SO:M:F:c:",
  236. options);
  237. while ((opt = gopt.getoption()) != -1) {
  238. switch (opt) {
  239. case 'w':
  240. AP_Param::erase_all();
  241. unlink(AP_Logger_SITL::filename);
  242. break;
  243. case 'u':
  244. AP_Param::set_hide_disabled_groups(false);
  245. break;
  246. case 's':
  247. speedup = strtof(gopt.optarg, nullptr);
  248. char speedup_string[18];
  249. snprintf(speedup_string, sizeof(speedup_string), "SIM_SPEEDUP=%s", gopt.optarg);
  250. _set_param_default(speedup_string);
  251. break;
  252. case 'r':
  253. _framerate = (unsigned)atoi(gopt.optarg);
  254. break;
  255. case 'C':
  256. HALSITL::UARTDriver::_console = true;
  257. break;
  258. case 'I': {
  259. _instance = atoi(gopt.optarg);
  260. if (_base_port == BASE_PORT) {
  261. _base_port += _instance * 10;
  262. }
  263. if (_rcin_port == RCIN_PORT) {
  264. _rcin_port += _instance * 10;
  265. }
  266. if (_fg_view_port == FG_VIEW_PORT) {
  267. _fg_view_port += _instance * 10;
  268. }
  269. if (simulator_port_in == SIM_IN_PORT) {
  270. simulator_port_in += _instance * 10;
  271. }
  272. if (simulator_port_out == SIM_OUT_PORT) {
  273. simulator_port_out += _instance * 10;
  274. }
  275. if (_irlock_port == IRLOCK_PORT) {
  276. _irlock_port += _instance * 10;
  277. }
  278. }
  279. break;
  280. case 'P':
  281. _set_param_default(gopt.optarg);
  282. break;
  283. case 'S':
  284. _synthetic_clock_mode = true;
  285. break;
  286. case 'O':
  287. home_str = gopt.optarg;
  288. break;
  289. case 'M':
  290. model_str = gopt.optarg;
  291. break;
  292. case 'c':
  293. config = gopt.optarg;
  294. break;
  295. case 'F':
  296. _fg_address = gopt.optarg;
  297. break;
  298. case CMDLINE_GIMBAL:
  299. enable_gimbal = true;
  300. break;
  301. case CMDLINE_FGVIEW:
  302. _use_fg_view = false;
  303. break;
  304. case CMDLINE_AUTOTESTDIR:
  305. autotest_dir = strdup(gopt.optarg);
  306. break;
  307. case CMDLINE_DEFAULTS:
  308. defaults_path = strdup(gopt.optarg);
  309. break;
  310. case CMDLINE_UARTA:
  311. case CMDLINE_UARTB:
  312. case CMDLINE_UARTC:
  313. case CMDLINE_UARTD:
  314. case CMDLINE_UARTE:
  315. case CMDLINE_UARTF:
  316. case CMDLINE_UARTG:
  317. case CMDLINE_UARTH:
  318. _uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
  319. break;
  320. case CMDLINE_RTSCTS:
  321. _use_rtscts = true;
  322. break;
  323. case CMDLINE_BASE_PORT:
  324. _base_port = atoi(gopt.optarg);
  325. break;
  326. case CMDLINE_RCIN_PORT:
  327. _rcin_port = atoi(gopt.optarg);
  328. break;
  329. case CMDLINE_SIM_ADDRESS:
  330. simulator_address = gopt.optarg;
  331. break;
  332. case CMDLINE_SIM_PORT_IN:
  333. simulator_port_in = atoi(gopt.optarg);
  334. break;
  335. case CMDLINE_SIM_PORT_OUT:
  336. simulator_port_out = atoi(gopt.optarg);
  337. break;
  338. case CMDLINE_IRLOCK_PORT:
  339. _irlock_port = atoi(gopt.optarg);
  340. break;
  341. default:
  342. _usage();
  343. exit(1);
  344. }
  345. }
  346. if (!model_str) {
  347. printf("You must specify a vehicle model\n");
  348. exit(1);
  349. }
  350. for (uint8_t i=0; i < ARRAY_SIZE(model_constructors); i++) {
  351. if (strncasecmp(model_constructors[i].name, model_str, strlen(model_constructors[i].name)) == 0) {
  352. // printf("Creating model %f,%f,%f,%f at speed %.1f\n", opos.lat, opos.lng, opos.alt, opos.hdg, speedup);
  353. sitl_model = model_constructors[i].constructor(model_str);
  354. if (home_str != nullptr) {
  355. Location home;
  356. float home_yaw;
  357. if (!parse_home(home_str, home, home_yaw)) {
  358. ::printf("Failed to parse home string (%s). Should be LAT,LON,ALT,HDG e.g. 37.4003371,-122.0800351,0,353\n", home_str);
  359. exit(1);
  360. }
  361. sitl_model->set_start_location(home, home_yaw);
  362. }
  363. sitl_model->set_interface_ports(simulator_address, simulator_port_in, simulator_port_out);
  364. sitl_model->set_speedup(speedup);
  365. sitl_model->set_instance(_instance);
  366. sitl_model->set_autotest_dir(autotest_dir);
  367. sitl_model->set_config(config);
  368. _synthetic_clock_mode = true;
  369. break;
  370. }
  371. }
  372. if (sitl_model == nullptr) {
  373. printf("Vehicle model (%s) not found\n", model_str);
  374. exit(1);
  375. }
  376. fprintf(stdout, "Starting sketch '%s'\n", SKETCH);
  377. if (strcmp(SKETCH, "ArduCopter") == 0) {
  378. _vehicle = ArduCopter;
  379. if (_framerate == 0) {
  380. _framerate = 200;
  381. }
  382. } else if (strcmp(SKETCH, "APMrover2") == 0) {
  383. _vehicle = APMrover2;
  384. if (_framerate == 0) {
  385. _framerate = 50;
  386. }
  387. // set right default throttle for rover (allowing for reverse)
  388. pwm_input[2] = 1500;
  389. } else if (strcmp(SKETCH, "ArduSub") == 0) {
  390. _vehicle = ArduSub;
  391. for(uint8_t i = 0; i < 8; i++) {
  392. pwm_input[i] = 1500;
  393. }
  394. } else {
  395. _vehicle = ArduPlane;
  396. if (_framerate == 0) {
  397. _framerate = 50;
  398. }
  399. }
  400. _sitl_setup(home_str);
  401. }
  402. /*
  403. parse a home string into a location and yaw
  404. */
  405. bool SITL_State::parse_home(const char *home_str, Location &loc, float &yaw_degrees)
  406. {
  407. char *saveptr = nullptr;
  408. char *s = strdup(home_str);
  409. if (!s) {
  410. free(s);
  411. ::printf("No home string supplied\n");
  412. return false;
  413. }
  414. char *lat_s = strtok_r(s, ",", &saveptr);
  415. if (!lat_s) {
  416. free(s);
  417. ::printf("Failed to parse latitude\n");
  418. return false;
  419. }
  420. char *lon_s = strtok_r(nullptr, ",", &saveptr);
  421. if (!lon_s) {
  422. free(s);
  423. ::printf("Failed to parse longitude\n");
  424. return false;
  425. }
  426. char *alt_s = strtok_r(nullptr, ",", &saveptr);
  427. if (!alt_s) {
  428. free(s);
  429. ::printf("Failed to parse altitude\n");
  430. return false;
  431. }
  432. char *yaw_s = strtok_r(nullptr, ",", &saveptr);
  433. if (!yaw_s) {
  434. free(s);
  435. ::printf("Failed to parse yaw\n");
  436. return false;
  437. }
  438. loc = {};
  439. loc.lat = static_cast<int32_t>(strtod(lat_s, nullptr) * 1.0e7);
  440. loc.lng = static_cast<int32_t>(strtod(lon_s, nullptr) * 1.0e7);
  441. loc.alt = static_cast<int32_t>(strtod(alt_s, nullptr) * 1.0e2);
  442. if (loc.lat == 0 && loc.lng == 0) {
  443. // default to CMAC instead of middle of the ocean. This makes
  444. // SITL in MissionPlanner a bit more useful
  445. loc.lat = -35.363261*1e7;
  446. loc.lng = 149.165230*1e7;
  447. loc.alt = 584*100;
  448. }
  449. yaw_degrees = strtof(yaw_s, nullptr);
  450. free(s);
  451. return true;
  452. }
  453. #endif