SITL: cmdline reorder help and param for better readability and futher extension

add missing options
This commit is contained in:
Pierre Kancir 2017-01-30 11:52:58 +01:00 committed by Andrew Tridgell
parent 29d35699f2
commit d4a0a92b8b

View File

@ -43,29 +43,35 @@ static void _sig_fpe(int signum)
void SITL_State::_usage(void)
{
printf("Options:\n"
"\t--home HOME set home location (lat,lng,alt,yaw)\n"
"\t--model MODEL set simulation model\n"
"\t--wipe wipe eeprom and dataflash\n"
"\t--unhide-groups parameter enumeration ignores AP_PARAM_FLAG_ENABLE\n"
"\t--speedup SPEEDUP set simulation speedup\n"
"\t--rate RATE set SITL framerate\n"
"\t--console use console instead of TCP ports\n"
"\t--instance N set instance of SITL (adds 10*instance to all port numbers)\n"
"\t--speedup SPEEDUP set simulation speedup\n"
// "\t--param NAME=VALUE set some param\n" CURRENTLY BROKEN!
"\t--synthetic-clock set synthetic clock mode\n"
"\t--home HOME set home location (lat,lng,alt,yaw)\n"
"\t--model MODEL set simulation model\n"
// "\t--client MODEL set client address string\n" NOT USED
"\t--gimbal enable simulated MAVLink gimbal\n"
"\t--disable-fgview disable Flight Gear view\n"
"\t--autotest-dir DIR set directory for additional files\n"
"\t--defaults path set path to defaults file\n"
"\t--uartA device set device string for UARTA\n"
"\t--uartB device set device string for UARTB\n"
"\t--uartC device set device string for UARTC\n"
"\t--uartD device set device string for UARTD\n"
"\t--uartE device set device string for UARTE\n"
"\t--uartF device set device string for UARTE\n"
"\t--rtscts enable rtscts on serial ports (default false)\n"
"\t--base-port PORT set port num for base port(default 5670) must be before -I option\n"
"\t--rc-in-port PORT set port num for rc in\n"
"\t--rc-out-port PORT set port num for rc out\n"
"\t--sim-address ADDR set address string for simulator\n"
"\t--sim-port-in PORT set port num for simulator in\n"
"\t--sim-port-out PORT set port num for simulator out\n"
"\t--irlock-port PORT set port num for irlock\n"
"\t--rc-in-port PORT set port num for rc in\n"
"\t--rc-out-port PORT set port num for rc out\n"
"\t--base-port PORT set port num for base port(default 5670) must be before -I option\n"
"\t--defaults path set path to defaults file\n"
);
}
@ -120,46 +126,40 @@ void SITL_State::_set_signal_handlers(void) const
void SITL_State::_parse_command_line(int argc, char * const argv[])
{
int opt;
float speedup = 1.0f;
_instance = 0;
_synthetic_clock_mode = false;
// default to CMAC
const char *home_str = "-35.363261,149.165230,584,353";
const char *model_str = nullptr;
_client_address = nullptr;
_use_fg_view = true;
char *autotest_dir = nullptr;
float speedup = 1.0f;
_fdm_address = "127.0.0.1";
if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) {
AP_HAL::panic("out of memory");
}
_set_signal_handlers();
setvbuf(stdout, (char *)0, _IONBF, 0);
setvbuf(stderr, (char *)0, _IONBF, 0);
_synthetic_clock_mode = false;
const int BASE_PORT = 5760;
const int RCOUT_PORT = 5502;
const int RCIN_PORT = 5501;
const int RCOUT_PORT = 5502;
const int FG_VIEW_PORT = 5503;
_base_port = BASE_PORT;
_rcin_port = RCIN_PORT;
_rcout_port = RCOUT_PORT;
_fg_view_port = FG_VIEW_PORT;
const int SIM_IN_PORT = 9003;
const int SIM_OUT_PORT = 9002;
const int IRLOCK_PORT = 9005;
_base_port = BASE_PORT;
_rcout_port = RCOUT_PORT;
_rcin_port = RCIN_PORT;
_fg_view_port = FG_VIEW_PORT;
_fdm_address = "127.0.0.1";
_client_address = nullptr;
_use_fg_view = true;
const char * _simulator_address = "127.0.0.1";
uint16_t _simulator_port_in = SIM_IN_PORT;
uint16_t _simulator_port_out = SIM_OUT_PORT;
_irlock_port = IRLOCK_PORT;
_instance = 0;
enum long_options {
CMDLINE_CLIENT=0,
CMDLINE_CLIENT = 0,
CMDLINE_GIMBAL,
CMDLINE_FGVIEW,
CMDLINE_AUTOTESTDIR,
CMDLINE_DEFAULTS,
CMDLINE_UARTA,
CMDLINE_UARTB,
CMDLINE_UARTC,
@ -167,15 +167,13 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
CMDLINE_UARTE,
CMDLINE_UARTF,
CMDLINE_RTSCTS,
CMDLINE_FGVIEW,
CMDLINE_BASE_PORT,
CMDLINE_RCIN_PORT,
CMDLINE_RCOUT_PORT,
CMDLINE_SIM_ADDRESS,
CMDLINE_SIM_PORT_IN,
CMDLINE_SIM_PORT_OUT,
CMDLINE_BASE_PORT,
CMDLINE_IRLOCK_PORT,
CMDLINE_RCIN_PORT,
CMDLINE_RCOUT_PORT,
CMDLINE_DEFAULTS
};
const struct GetOptLong::option options[] = {
@ -190,27 +188,36 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
{"synthetic-clock", false, 0, 'S'},
{"home", true, 0, 'O'},
{"model", true, 0, 'M'},
{"client", true, 0, CMDLINE_CLIENT},
{"gimbal", false, 0, CMDLINE_GIMBAL},
{"disable-fgview", false, 0, CMDLINE_FGVIEW},
{"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
{"defaults", true, 0, CMDLINE_DEFAULTS},
{"uartA", true, 0, CMDLINE_UARTA},
{"uartB", true, 0, CMDLINE_UARTB},
{"uartC", true, 0, CMDLINE_UARTC},
{"uartD", true, 0, CMDLINE_UARTD},
{"uartE", true, 0, CMDLINE_UARTE},
{"client", true, 0, CMDLINE_CLIENT},
{"gimbal", false, 0, CMDLINE_GIMBAL},
{"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
{"defaults", true, 0, CMDLINE_DEFAULTS},
{"uartF", true, 0, CMDLINE_UARTF},
{"rtscts", false, 0, CMDLINE_RTSCTS},
{"disable-fgview", false, 0, CMDLINE_FGVIEW},
{"base-port", true, 0, CMDLINE_BASE_PORT},
{"rc-in-port", true, 0, CMDLINE_RCIN_PORT},
{"rc-out-port", true, 0, CMDLINE_RCOUT_PORT},
{"sim-address", true, 0, CMDLINE_SIM_ADDRESS},
{"sim-port-in", true, 0, CMDLINE_SIM_PORT_IN},
{"sim-port-out", true, 0, CMDLINE_SIM_PORT_OUT},
{"base-port", true, 0, CMDLINE_BASE_PORT},
{"irlock-port", true, 0, CMDLINE_IRLOCK_PORT},
{"rc-in-port", true, 0, CMDLINE_RCIN_PORT},
{"rc-out-port", true, 0, CMDLINE_RCOUT_PORT},
{0, false, 0, 0}
};
if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) {
AP_HAL::panic("out of memory");
}
_set_signal_handlers();
setvbuf(stdout, (char *)0, _IONBF, 0);
setvbuf(stderr, (char *)0, _IONBF, 0);
GetOptLong gopt(argc, argv, "hwus:r:CI:P:SO:M:F:",
options);
@ -223,6 +230,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case 'u':
AP_Param::set_hide_disabled_groups(false);
break;
case 's':
speedup = strtof(gopt.optarg, nullptr);
break;
case 'r':
_framerate = (unsigned)atoi(gopt.optarg);
break;
@ -266,9 +276,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case 'M':
model_str = gopt.optarg;
break;
case 's':
speedup = strtof(gopt.optarg, nullptr);
break;
case 'F':
_fdm_address = gopt.optarg;
break;
@ -278,8 +285,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case CMDLINE_GIMBAL:
enable_gimbal = true;
break;
case CMDLINE_RTSCTS:
_use_rtscts = true;
case CMDLINE_FGVIEW:
_use_fg_view = false;
break;
case CMDLINE_AUTOTESTDIR:
autotest_dir = strdup(gopt.optarg);
@ -287,7 +294,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case CMDLINE_DEFAULTS:
defaults_path = strdup(gopt.optarg);
break;
case CMDLINE_UARTA:
case CMDLINE_UARTB:
case CMDLINE_UARTC:
@ -296,8 +302,17 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case CMDLINE_UARTF:
_uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
break;
case CMDLINE_FGVIEW:
_use_fg_view = false;
case CMDLINE_RTSCTS:
_use_rtscts = true;
break;
case CMDLINE_BASE_PORT:
_base_port = atoi(gopt.optarg);
break;
case CMDLINE_RCIN_PORT:
_rcin_port = atoi(gopt.optarg);
break;
case CMDLINE_RCOUT_PORT:
_rcout_port = atoi(gopt.optarg);
break;
case CMDLINE_SIM_ADDRESS:
_simulator_address = gopt.optarg;
@ -311,15 +326,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case CMDLINE_IRLOCK_PORT:
_irlock_port = atoi(gopt.optarg);
break;
case CMDLINE_RCIN_PORT:
_rcin_port = atoi(gopt.optarg);
break;
case CMDLINE_RCOUT_PORT:
_rcout_port = atoi(gopt.optarg);
break;
case CMDLINE_BASE_PORT:
_base_port = atoi(gopt.optarg);
break;
default:
_usage();
exit(1);