Skip to content

Commit

Permalink
Merge pull request #48 from knorth55/remove-smach-image
Browse files Browse the repository at this point in the history
[smach_viewer] remove smach image in /tmp when the node is killed
  • Loading branch information
k-okada authored Oct 26, 2022
2 parents 8cc7ab3 + 63cf7e8 commit 2f7a4c8
Showing 1 changed file with 10 additions and 0 deletions.
10 changes: 10 additions & 0 deletions smach_viewer/scripts/smach_image_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import rospy
import subprocess
import sys
import time

from sensor_msgs.msg import CompressedImage
from sensor_msgs.msg import Image
Expand Down Expand Up @@ -123,6 +124,14 @@ def _timer_cb(self, event):
cv2.imencode('.jpg', img)[1]).tostring()
self._pub_compressed.publish(compressed_img_msg)

def remove_file(self):
# wait and loop until file is removed
while os.path.exists(self.filepath):
rospy.logwarn(
'Removing file: {}'.format(self.filepath))
os.remove(self.filepath)
time.sleep(0.1)


if __name__ == '__main__':
rospy.init_node('smach_image_publisher')
Expand All @@ -131,6 +140,7 @@ def _timer_cb(self, event):
def signal_handler():
rospy.logwarn('Killing threads...')
app.kill()
app.remove_file()

rospy.on_shutdown(signal_handler)
rospy.spin()

0 comments on commit 2f7a4c8

Please sign in to comment.