diff --git a/clients/rospy/src/rospy/impl/registration.py b/clients/rospy/src/rospy/impl/registration.py index 4a18c85f2c..6837de602c 100644 --- a/clients/rospy/src/rospy/impl/registration.py +++ b/clients/rospy/src/rospy/impl/registration.py @@ -315,7 +315,7 @@ def run(self): for uri in uris: # #1141: have to multithread this to prevent a bad publisher from hanging us t = threading.Thread(target=self._connect_topic_thread, args=(topic, uri)) - t.setDaemon(True) + t.daemon = True t.start() def _connect_topic_thread(self, topic, uri): diff --git a/clients/rospy/src/rospy/impl/tcpros_base.py b/clients/rospy/src/rospy/impl/tcpros_base.py index 021768bf61..430bca9d04 100644 --- a/clients/rospy/src/rospy/impl/tcpros_base.py +++ b/clients/rospy/src/rospy/impl/tcpros_base.py @@ -138,7 +138,7 @@ def __init__(self, inbound_handler, port=0): def start(self): """Runs the run() loop in a separate thread""" t = threading.Thread(target=self.run, args=()) - t.setDaemon(True) + t.daemon = True t.start() def run(self): diff --git a/clients/rospy/src/rospy/impl/tcpros_service.py b/clients/rospy/src/rospy/impl/tcpros_service.py index 6298a81534..aea221b046 100644 --- a/clients/rospy/src/rospy/impl/tcpros_service.py +++ b/clients/rospy/src/rospy/impl/tcpros_service.py @@ -249,7 +249,7 @@ def service_connection_handler(sock, client_addr, header): # using threadpool reduced performance by an order of # magnitude, need to investigate better t = threading.Thread(target=service.handle, args=(transport, header)) - t.setDaemon(True) + t.daemon = True t.start() diff --git a/clients/rospy/src/rospy/timer.py b/clients/rospy/src/rospy/timer.py index 71d14aed9c..f283130598 100644 --- a/clients/rospy/src/rospy/timer.py +++ b/clients/rospy/src/rospy/timer.py @@ -207,7 +207,7 @@ def __init__(self, period, callback, oneshot=False, reset=False): self._oneshot = oneshot self._reset = reset self._shutdown = False - self.setDaemon(True) + self.daemon = True self.start() def shutdown(self): diff --git a/test/test_rospy/test/unit/test_rospy_rostime.py b/test/test_rospy/test/unit/test_rospy_rostime.py index c4b7f988a6..d5a9e14b5a 100644 --- a/test/test_rospy/test/unit/test_rospy_rostime.py +++ b/test/test_rospy/test/unit/test_rospy_rostime.py @@ -333,7 +333,7 @@ def test_sleep(self): #start sleeper self.failIf(test_sleep_done) sleepthread = threading.Thread(target=sleeper, args=()) - sleepthread.setDaemon(True) + sleepthread.daemon = True sleepthread.start() time.sleep(1.0) #make sure thread is spun up self.failIf(test_sleep_done) @@ -346,7 +346,7 @@ def test_sleep(self): #start duration sleeper self.failIf(test_duration_sleep_done) dursleepthread = threading.Thread(target=duration_sleeper, args=()) - dursleepthread.setDaemon(True) + dursleepthread.daemon = True dursleepthread.start() time.sleep(1.0) #make sure thread is spun up self.failIf(test_duration_sleep_done) @@ -359,7 +359,7 @@ def test_sleep(self): #start backwards sleeper self.failIf(test_backwards_sleep_done) backsleepthread = threading.Thread(target=backwards_sleeper, args=()) - backsleepthread.setDaemon(True) + backsleepthread.daemon = True backsleepthread.start() time.sleep(1.0) #make sure thread is spun up self.failIf(test_backwards_sleep_done) diff --git a/tools/roslaunch/src/roslaunch/pmon.py b/tools/roslaunch/src/roslaunch/pmon.py index b20a90485b..5550971b1c 100644 --- a/tools/roslaunch/src/roslaunch/pmon.py +++ b/tools/roslaunch/src/roslaunch/pmon.py @@ -313,7 +313,7 @@ def __init__(self, name="ProcessMonitor"): self.plock = RLock() self.is_shutdown = False self.done = False - self.setDaemon(True) + self.daemon = True self.reacquire_signals = set() self.listeners = [] self.dead_list = [] diff --git a/tools/roslaunch/test/unit/test_roslaunch_pmon.py b/tools/roslaunch/test/unit/test_roslaunch_pmon.py index abca7cdba6..5664e7aa84 100644 --- a/tools/roslaunch/test/unit/test_roslaunch_pmon.py +++ b/tools/roslaunch/test/unit/test_roslaunch_pmon.py @@ -399,7 +399,7 @@ def f(): # and run it -- but setup a safety timer to kill it if it doesn't exit marker = Marker() t = threading.Thread(target=kill_pmon, args=(pmon, marker, 10.)) - t.setDaemon(True) + t.daemon = True t.start() pmon.run() @@ -455,7 +455,7 @@ def f(): # and run it -- but setup a safety timer to kill it if it doesn't exit marker = Marker() t = threading.Thread(target=kill_pmon, args=(self.pmon, marker, 10.)) - t.setDaemon(True) + t.daemon = True t.start() pmon.run() @@ -565,7 +565,7 @@ def test_mainthread_spin(self): # can't test actual spin as that would go forever self.pmon.done = False t = threading.Thread(target=kill_pmon, args=(self.pmon, Marker())) - t.setDaemon(True) + t.daemon = True t.start() self.pmon.mainthread_spin() diff --git a/tools/rosmaster/src/rosmaster/threadpool.py b/tools/rosmaster/src/rosmaster/threadpool.py index 8e7cbff0e4..6d195dcaea 100644 --- a/tools/rosmaster/src/rosmaster/threadpool.py +++ b/tools/rosmaster/src/rosmaster/threadpool.py @@ -198,7 +198,7 @@ class ThreadPoolThread(threading.Thread): def __init__(self, pool): """Initialize the thread and remember the pool.""" threading.Thread.__init__(self) - self.setDaemon(True) #don't block program exit + self.daemon = True #don't block program exit self.__pool = pool self.__isDying = False