diff --git a/ur_driver/prog b/ur_driver/prog
index 653b1f514add2419de26771613f56d253b457980..572a09eb4bab511685a662acc9b020311870903a 100644
--- a/ur_driver/prog
+++ b/ur_driver/prog
@@ -116,18 +116,9 @@ def driverProg():
       exit_critical
     end
     
-    #temporarily reduce publish rate for io_states
-    io_count = 0
-    io_slowdown_ratio = 10
-    
     send_io_state()
     while True:
-      if io_count != io_slowdown_ratio:
-        io_count=io_count+1
-      else:
-        send_io_state()
-        io_count=0
-      end
+      send_io_state()
       sync()
     end
     sync()
diff --git a/ur_driver/src/ur_driver/io_interface.py b/ur_driver/src/ur_driver/io_interface.py
index a7fa6d7ba65bdb9ac2509fdf4937a9076afbf0de..3e0a44c0dbaac06a98069899b73e5153a2fb619c 100644
--- a/ur_driver/src/ur_driver/io_interface.py
+++ b/ur_driver/src/ur_driver/io_interface.py
@@ -50,9 +50,9 @@ def set_flag(pin, val):
         set_digital_out(pin, val)
 
 def callback(data):
-    for i in range(0,32):
-        del Flag_States[i]
-        Flag_States.insert(i, data.flag_states[i].state)
+    #for i in range(0,32):
+        #del Flag_States[i]
+        #Flag_States.insert(i, data.flag_states[i].state)
     for i in range(0,10):
         del Digital_Out_States[i]
         Digital_Out_States.insert(i, data.digital_out_states[i].state)
diff --git a/ur_driver/test_io.py b/ur_driver/test_io.py
index 1d62d1703f8026e7d31ae11c20cda9352a45c358..a38be3c104fef883aa38bec998731893e47dadbb 100755
--- a/ur_driver/test_io.py
+++ b/ur_driver/test_io.py
@@ -10,16 +10,18 @@ if __name__ == "__main__":
         set_tool_voltage(12)
         set_digital_out(0, True)
         set_analog_out(0, 0.75)
-        set_flag(0, True)
-        print(Flag_States[0])
+        print "Flags are currently not supported"
+        #set_flag(0, True)
+        #print(Flag_States[0])
         print(Analog_Out_States[0])
         print(Digital_Out_States[0])
         time.sleep(1)
         set_tool_voltage(24)
         set_digital_out(0, False)
         set_analog_out(0, 0.25)
-        set_flag(0, False)
-        print(Flag_States[0])
+        print "Flags are currently not supported"
+        #set_flag(0, False)
+        #print(Flag_States[0])
         print(Analog_Out_States[0])
         print(Digital_Out_States[0])
         time.sleep(1)