mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: added --autotest-dir option
This commit is contained in:
parent
4f37926aea
commit
3daee9c8bc
|
@ -42,6 +42,7 @@ void SITL_State::_usage(void)
|
|||
"\t--instance N set instance of SITL (adds 10*instance to all port numbers)\n"
|
||||
"\t--speedup SPEEDUP set simulation speedup\n"
|
||||
"\t--gimbal enable simulated MAVLink gimbal\n"
|
||||
"\t--autotest-dir DIR set directory for additional files\n"
|
||||
);
|
||||
}
|
||||
|
||||
|
@ -67,8 +68,11 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
int opt;
|
||||
const char *home_str = NULL;
|
||||
const char *model_str = NULL;
|
||||
char *autotest_dir = NULL;
|
||||
float speedup = 1.0f;
|
||||
|
||||
asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest");
|
||||
|
||||
signal(SIGFPE, _sig_fpe);
|
||||
// No-op SIGPIPE handler
|
||||
signal(SIGPIPE, SIG_IGN);
|
||||
|
@ -86,7 +90,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
|
||||
enum long_options {
|
||||
CMDLINE_CLIENT=0,
|
||||
CMDLINE_GIMBAL
|
||||
CMDLINE_GIMBAL,
|
||||
CMDLINE_AUTOTESTDIR
|
||||
};
|
||||
|
||||
const struct GetOptLong::option options[] = {
|
||||
|
@ -102,6 +107,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
{"model", true, 0, 'M'},
|
||||
{"client", true, 0, CMDLINE_CLIENT},
|
||||
{"gimbal", false, 0, CMDLINE_GIMBAL},
|
||||
{"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
|
||||
{0, false, 0, 0}
|
||||
};
|
||||
|
||||
|
@ -151,6 +157,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
case CMDLINE_GIMBAL:
|
||||
enable_gimbal = true;
|
||||
break;
|
||||
case CMDLINE_AUTOTESTDIR:
|
||||
autotest_dir = strdup(gopt.optarg);
|
||||
break;
|
||||
default:
|
||||
_usage();
|
||||
exit(1);
|
||||
|
@ -163,6 +172,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
sitl_model = model_constructors[i].constructor(home_str, model_str);
|
||||
sitl_model->set_speedup(speedup);
|
||||
sitl_model->set_instance(_instance);
|
||||
sitl_model->set_autotest_dir(autotest_dir);
|
||||
_synthetic_clock_mode = true;
|
||||
printf("Started model %s at %s at speed %.1f\n", model_str, home_str, speedup);
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue