1+ /* ********************************************************************
2+ * This software is factored out from the ros_control hardware interface
3+ * for Universal Robots manipulators. The software assigns the highest
4+ * realtime priority to the currently running thread.
5+ * You can find the original work at
6+ *
7+ * https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/tree/395c054/ur_robot_driver
8+ * https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/blob/395c054/ur_robot_driver/src/hardware_interface_node.cpp#L63
9+ *
10+ * Copyright 2019 FZI Forschungszentrum Informatik
11+ * Created on behalf of Universal Robots A/S
12+ *
13+ * Licensed under the Apache License, Version 2.0 (the "License");
14+ * you may not use this file except in compliance with the License.
15+ * You may obtain a copy of the License at
16+ *
17+ * http://www.apache.org/licenses/LICENSE-2.0
18+ *
19+ * Unless required by applicable law or agreed to in writing, software
20+ * distributed under the License is distributed on an "AS IS" BASIS,
21+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22+ * See the License for the specific language governing permissions and
23+ * limitations under the License.
24+ *********************************************************************/
25+
26+ /*
27+ * Author: Felix Exner <[email protected] > 28+ */
29+
30+ #ifndef KUKA_RSI_HARDWARE_INTERFACE_ASSIGN_RT_PRIORITY_
31+ #define KUKA_RSI_HARDWARE_INTERFACE_ASSIGN_RT_PRIORITY_
32+
33+ #include < fstream>
34+ #include < ros/ros.h>
35+
36+ namespace kuka_rsi_hw_interface
37+ {
38+ void assign_max_rt_priority ()
39+ {
40+ std::ifstream realtime_file (" /sys/kernel/realtime" , std::ios::in);
41+ bool has_realtime = false ;
42+ if (realtime_file.is_open ())
43+ {
44+ realtime_file >> has_realtime;
45+ }
46+ if (has_realtime)
47+ {
48+ const int max_thread_priority = sched_get_priority_max (SCHED_FIFO);
49+ if (max_thread_priority != -1 )
50+ {
51+ // We'll operate on the currently running thread.
52+ pthread_t this_thread = pthread_self ();
53+
54+ // struct sched_param is used to store the scheduling priority
55+ struct sched_param params;
56+
57+ // We'll set the priority to the maximum.
58+ params.sched_priority = max_thread_priority;
59+
60+ int ret = pthread_setschedparam (this_thread, SCHED_FIFO, ¶ms);
61+ if (ret != 0 )
62+ {
63+ ROS_ERROR_STREAM (" Unsuccessful in setting main thread realtime priority. Error code: " << ret);
64+ }
65+ // Now verify the change in thread priority
66+ int policy = 0 ;
67+ ret = pthread_getschedparam (this_thread, &policy, ¶ms);
68+ if (ret != 0 )
69+ {
70+ ROS_ERROR_STREAM (" Couldn't retrieve real-time scheduling parameters" );
71+ }
72+
73+ // Check the correct policy was applied
74+ if (policy != SCHED_FIFO)
75+ {
76+ ROS_ERROR (" Main thread: Scheduling is NOT SCHED_FIFO!" );
77+ }
78+ else
79+ {
80+ ROS_INFO (" Main thread: SCHED_FIFO OK" );
81+ }
82+
83+ // Print thread scheduling priority
84+ ROS_INFO_STREAM (" Main thread priority is " << params.sched_priority );
85+ }
86+ else
87+ {
88+ ROS_ERROR (" Could not get maximum thread priority for main thread" );
89+ }
90+ }
91+ }
92+ } // namespace kuka_rsi_hardware_interface
93+
94+ #endif /* KUKA_RSI_HARDWARE_INTERFACE_ASSIGN_RT_PRIORITY_ */
0 commit comments