diff --git a/launch/msckf_vio_tinytum.launch b/launch/msckf_vio_tinytum.launch
index 12fcaee..94deb7c 100644
--- a/launch/msckf_vio_tinytum.launch
+++ b/launch/msckf_vio_tinytum.launch
@@ -72,7 +72,8 @@
-
+
+
diff --git a/src/control.py b/src/control.py
new file mode 100755
index 0000000..3292b5b
--- /dev/null
+++ b/src/control.py
@@ -0,0 +1,64 @@
+#!/usr/bin/env python
+import rosbag
+import rospy
+from sensor_msgs.msg import Imu, Image
+from geometry_msgs.msg import TransformStamped
+import time
+import signal
+import sys
+
+
+def signal_handler(sig, frame):
+ print('gracefully exiting the program.')
+ bag.close()
+ sys.exit(0)
+
+def main():
+ global bag
+
+ cam0_topic = '/cam0/image_raw'
+ cam1_topic = '/cam1/image_raw'
+ imu0_topic = '/imu0'
+ grnd_topic = '/vrpn_client/raw_transform'
+
+ rospy.init_node('controlbag')
+ rospy.set_param('play_bag', False)
+
+ cam0_pub = rospy.Publisher(cam0_topic, Image, queue_size=10)
+ cam1_pub = rospy.Publisher(cam1_topic, Image, queue_size=10)
+ imu0_pub = rospy.Publisher(imu0_topic, Imu, queue_size=10)
+ grnd_pub = rospy.Publisher(grnd_topic, TransformStamped, queue_size=10)
+
+ signal.signal(signal.SIGINT, signal_handler)
+
+ bag = rosbag.Bag('/home/raphael/dev/MSCKF_ws/bag/TUM/dataset-corridor1_1024_16.bag')
+ for topic, msg, t in bag.read_messages(topics=[cam0_topic, cam1_topic, imu0_topic, grnd_topic]):
+
+ # pause if parameter set to false
+ flag = False
+ while not rospy.get_param('/play_bag'):
+ time.sleep(0.01)
+ if not flag:
+ print("stopped playback")
+ flag = not flag
+
+ if flag:
+ print("resume playback")
+
+ if topic == cam0_topic:
+ cam0_pub.publish(msg)
+
+ elif topic == cam1_topic:
+ cam1_pub.publish(msg)
+
+ elif topic == imu0_topic:
+ imu0_pub.publish(msg)
+
+ elif topic ==grnd_topic:
+ grnd_pub.publish(msg)
+
+ #print msg
+ bag.close()
+
+if __name__== "__main__":
+ main()
\ No newline at end of file