Skip to content
Snippets Groups Projects
Commit 4062352e authored by Alexis Nicolin's avatar Alexis Nicolin Committed by Olivier Stasse
Browse files

Fixed the AsyncSpinner scheduler and priority

parent 28bfd530
No related branches found
No related tags found
No related merge requests found
...@@ -37,12 +37,33 @@ namespace dynamicgraph ...@@ -37,12 +37,33 @@ namespace dynamicgraph
if (!ros.spinner && createAsyncSpinner) if (!ros.spinner && createAsyncSpinner)
{ {
ros.spinner = boost::make_shared<ros::AsyncSpinner> (4); ros.spinner = boost::make_shared<ros::AsyncSpinner> (4);
// Change the thread's scheduler from real-time to normal and reduce its priority
int oldThreadPolicy, newThreadPolicy;
struct sched_param oldThreadParam, newThreadParam;
if (pthread_getschedparam (pthread_self(), &oldThreadPolicy, &oldThreadParam) == 0)
{
newThreadPolicy = SCHED_OTHER;
newThreadParam = oldThreadParam;
newThreadParam.sched_priority -= 5; // Arbitrary number, TODO: choose via param/file?
if (newThreadParam.sched_priority < sched_get_priority_min (newThreadPolicy))
newThreadParam.sched_priority = sched_get_priority_min (newThreadPolicy);
pthread_setschedparam (pthread_self(), newThreadPolicy, &newThreadParam);
}
// AsyncSpinners are created with the reduced priority
ros.spinner->start (); ros.spinner->start ();
// Switch the priority of the parent thread (this thread) back to real-time.
pthread_setschedparam (pthread_self(), oldThreadPolicy, &oldThreadParam);
} }
else else
{ {
if (!ros.mtSpinner && createMultiThreadedSpinner) if (!ros.mtSpinner && createMultiThreadedSpinner)
{ {
// Seems not to be used.
// If we need to reduce its threads priority, it needs to be done before calling the MultiThreadedSpinner::spin() method
ros.mtSpinner = boost::make_shared<ros::MultiThreadedSpinner>(4); ros.mtSpinner = boost::make_shared<ros::MultiThreadedSpinner>(4);
} }
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment