|
|
|
@ -113,6 +113,7 @@ void SITL_State::_usage(void)
@@ -113,6 +113,7 @@ void SITL_State::_usage(void)
|
|
|
|
|
"\t--irlock-port PORT set port num for irlock\n" |
|
|
|
|
"\t--start-time TIMESTR set simulation start time in UNIX timestamp\n" |
|
|
|
|
"\t--sysid ID set SYSID_THISMAV\n" |
|
|
|
|
"\t--slave number set the number of JSON slaves\n" |
|
|
|
|
); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -260,6 +261,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
@@ -260,6 +261,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|
|
|
|
CMDLINE_IRLOCK_PORT, |
|
|
|
|
CMDLINE_START_TIME, |
|
|
|
|
CMDLINE_SYSID, |
|
|
|
|
CMDLINE_SLAVE, |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
const struct GetOptLong::option options[] = { |
|
|
|
@ -307,6 +309,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
@@ -307,6 +309,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|
|
|
|
{"irlock-port", true, 0, CMDLINE_IRLOCK_PORT}, |
|
|
|
|
{"start-time", true, 0, CMDLINE_START_TIME}, |
|
|
|
|
{"sysid", true, 0, CMDLINE_SYSID}, |
|
|
|
|
{"slave", true, 0, CMDLINE_SLAVE}, |
|
|
|
|
{0, false, 0, 0} |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
@ -462,6 +465,13 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
@@ -462,6 +465,13 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|
|
|
|
case 'h': |
|
|
|
|
_usage(); |
|
|
|
|
exit(0); |
|
|
|
|
case CMDLINE_SLAVE: { |
|
|
|
|
const int32_t slaves = atoi(gopt.optarg); |
|
|
|
|
if (slaves > 0) { |
|
|
|
|
ride_along.init(slaves); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
default: |
|
|
|
|
_usage(); |
|
|
|
|
exit(1); |
|
|
|
|