diff --git a/python/examples/graz/ros1_to_protobuf.py b/python/examples/graz/ros1_to_protobuf.py
index 53fa8a7a83198c4a562700c9fa3b8b91c0bb5ee6..890f7fc7906ab15ec891e7592829e306c5f047cd 100644
--- a/python/examples/graz/ros1_to_protobuf.py
+++ b/python/examples/graz/ros1_to_protobuf.py
@@ -5,6 +5,7 @@ import message_specs_pb2
 import time
 from agents_test.msg import Command
 import rospy
+from functools import partial
 
 
 
@@ -18,8 +19,8 @@ def getArgs():
 	return args
 
 
-def callback(c):
-    print("received callback")
+def callback(comm_socket, c):
+    #print("received callback")
     position = [c.goal.position.x, c.goal.position.y, c.goal.position.z]
     orientation = [c.goal.orientation.w, c.goal.orientation.x, c.goal.orientation.y, c.goal.orientation.z]
     position_vel = [c.goal_dot.position.x, c.goal_dot.position.y, c.goal_dot.position.z]
@@ -28,7 +29,7 @@ def callback(c):
     pb2_msg.position.extend(position)
     pb2_msg.rotation.extend(orientation)
     pb2_msg.velocity.extend(position_vel + orientation_vel)
-    print(pb2_msg)
+    #print(pb2_msg)
     msg_length = pb2_msg.ByteSize()
     msg_serialized = pb2_msg.SerializeToString()
     msg = _VarintBytes(msg_length) + msg_serialized
@@ -49,7 +50,8 @@ if __name__ == "__main__":
     print("NETWORKING_SERVER: accepted a client", comm_addr)
 
     # ros subscriber
-    rospy.Subscriber("/robot_command", Command, callback)
+    callback_part = partial(callback, comm_socket)
+    rospy.Subscriber("/robot_command", Command, callback_part)
     rospy.spin()
 
     comm_socket.close()