Use delay API

This commit is contained in:
Lorenz Meier
2016-02-05 00:53:22 +01:00
parent 61fac4a127
commit 8e62c9eb8d
2 changed files with 23 additions and 3 deletions

View File

@@ -175,11 +175,15 @@ extern "C" {
if (strcmp(argv[2], "-s") == 0 ||
strcmp(argv[2], "-p") == 0 ||
strcmp(argv[2], "-t") == 0) {
if (g_sim_task >= 0) {
warnx("Simulator already started");
return 0;
}
// enable lockstep support
px4_enable_sim_lockstep();
g_sim_task = px4_task_spawn_cmd("simulator",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX,