Go to the documentation of this file.00001
00002 import rospy, subprocess
00003 import time
00004 from std_msgs.msg import Bool
00005 from std_msgs.msg import String
00006 from diagnostic_msgs.msg import *
00007 from misc_msgs.srv import RosbagControl, RosbagControlResponse
00008
00009 class RosbagMonitor():
00010
00011 def __init__(self):
00012 self.setup()
00013 pass
00014
00015 def setup(self):
00016
00017 rospy.init_node('rosbag_monitor', anonymous=True)
00018 save_directory = rospy.get_param('~save_directory')
00019 self.rosbagActions = {'start': 'rosbag record -a -o '+str(save_directory)+'rosbag', 'split': ''}
00020 self.loggerActive = False;
00021 ''' Publishers and subscribers '''
00022 self.subRosbagAction = rospy.Subscriber("rosbagAction", String, self.onRosbagActionCallback)
00023 ''' Service '''
00024 self.srvRosbag = rospy.Service('rosbagAction',RosbagControl,self.rosbagService)
00025 rospy.spin()
00026 pass
00027
00028 def rosbagControl(self,action):
00029 if action=='stop':
00030 if self.loggerActive == True:
00031 rospy.logerr("Stopping Rosbag logger...")
00032 self.proc.terminate()
00033 self.proc.wait()
00034 self.loggerActive = False
00035 else:
00036 rospy.logerr("No Active log...")
00037 elif action=='start':
00038 if self.loggerActive == True:
00039 self.proc.terminate()
00040 self.proc.wait()
00041 rospy.logerr("Starting Rosbag logger...")
00042 self.proc = subprocess.Popen(self.rosbagActions['start'].split(" "))
00043 self.loggerActive = True
00044
00045 def rosbagService(self,req):
00046 self.rosbagControl(req.action)
00047 return RosbagControlResponse(self.loggerActive)
00048
00049 def onRosbagActionCallback(self, msg):
00050 self.rosbagControl(msg.data)
00051
00052 if __name__ == '__main__':
00053 try:
00054 RBM = RosbagMonitor()
00055 except rospy.ROSInterruptException: pass
00056
00057