rosbag_record_server.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 import roslib
00005 
00006 import os
00007 import subprocess
00008 roslib.load_manifest("rwt_image_view")
00009 
00010 from rwt_image_view.srv import *
00011 from std_srvs.srv import *
00012 import signal
00013 
00014 g_pobj = None
00015 
00016 def rosbagRecordRequestCB(req):
00017     global g_pobj
00018     rospy.loginfo("topics: " + str(req.topics))
00019     record_path = roslib.packages.find_node("rosbag", "record")
00020     args = [record_path[0], "-O", os.path.join(os.path.dirname(__file__), "..", "www", "tmp.bag")] + req.topics
00021     g_pobj = subprocess.Popen(args)
00022     return RosbagRecordRequestResponse()
00023 
00024 def rosbagRecordStopCB(req):
00025     global g_pobj
00026     if g_pobj:
00027         rospy.loginfo("sending SIGINT")
00028         g_pobj.send_signal(signal.SIGINT)
00029         #os.kill(g_pobj.pid, signal.SIGINT)
00030         g_pobj = None
00031     return EmptyResponse()
00032 
00033 def main():
00034     rospy.init_node("rosbag_record_server")
00035     s1 = rospy.Service('rosbag_record', RosbagRecordRequest, rosbagRecordRequestCB)
00036     s2 = rospy.Service('rosbag_record_stop', Empty, rosbagRecordStopCB)
00037     rospy.spin()
00038 
00039 if __name__ == "__main__":
00040    main()


rwt_image_view
Author(s): Ryohei Ueda , Yuki Furuta
autogenerated on Mon Oct 3 2016 03:40:23