diff --git a/src/modules/simulator/simulator.cpp b/src/modules/simulator/simulator.cpp index b732945f7b..bcd188b0f0 100644 --- a/src/modules/simulator/simulator.cpp +++ b/src/modules/simulator/simulator.cpp @@ -182,7 +182,7 @@ extern "C" { g_sim_task = px4_task_spawn_cmd("simulator", SCHED_DEFAULT, - SCHED_PRIORITY_MAX - 5, + SCHED_PRIORITY_MAX, 1500, Simulator::start, argv); diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 4ea56156ac..a10c89792d 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -457,7 +457,7 @@ void Simulator::pollForMAVLinkMessages(bool publish) (void)pthread_attr_getschedparam(&sender_thread_attr, ¶m); /* low priority */ - param.sched_priority = SCHED_PRIORITY_DEFAULT; + param.sched_priority = SCHED_PRIORITY_DEFAULT + 40; (void)pthread_attr_setschedparam(&sender_thread_attr, ¶m); // setup serial connection to autopilot (used to get manual controls) @@ -533,11 +533,11 @@ void Simulator::pollForMAVLinkMessages(bool publish) // wait for new mavlink messages to arrive while (true) { - pret = ::poll(&fds[0], fd_count, 100); + pret = ::poll(&fds[0], fd_count, 10); //timed out if (pret == 0) { - PX4_WARN("mavlink sim timeout for 100 ms"); + PX4_WARN("mavlink sim timeout for 10 ms"); continue; }