We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent edaf31a commit e8c1660Copy full SHA for e8c1660
rqt_gui_py/src/rqt_gui_py/rclpy_spinner.py
@@ -14,7 +14,7 @@
14
15
from python_qt_binding.QtCore import qDebug, QThread
16
import rclpy
17
-from rclpy.executors import MultiThreadedExecutor
+from rclpy.executors import SingleThreadedExecutor
18
19
20
class RclpySpinner(QThread):
@@ -26,7 +26,7 @@ def __init__(self, node):
26
27
def run(self):
28
qDebug('Start called on RclpySpinner, spinning ros2 node')
29
- executor = MultiThreadedExecutor()
+ executor = SingleThreadedExecutor()
30
executor.add_node(self._node)
31
while rclpy.ok() and not self._abort:
32
executor.spin_once(timeout_sec=1.0)
0 commit comments