diff --git a/scripts/plotter.py b/scripts/plotter.py
index bb3445c85085f38d7e6ca8623fd0922a466e8c27..3a9ae7c0032fa9f2be960620f054f88cb8d9bb8b 100755
--- a/scripts/plotter.py
+++ b/scripts/plotter.py
@@ -3,16 +3,43 @@ from matplotlib import pyplot as plt
 import rospy
 from panda_mqtt_connector.msg import StampedVelocity
 
-def plot_x(msg):
-    plt.plot(msg.header.stamp.to_sec(), msg.velocity, '*')
-    plt.axis("equal")
-    plt.draw()
-    plt.pause(0.00000000001)
+import numpy as np
+import matplotlib.pyplot as plt
+from matplotlib.animation import FuncAnimation
+
+new_velocity = []
+
+fig, ax = plt.subplots()
+xdata_velocity, ydata_velocity = [], []
+ln, = plt.plot([], [], 'ro')
+
+def callback_velocity(msg):
+    global new_velocity
+    new_velocity += [msg]
+
+def init_velocity():
+    ax.set_xlim(0, 150)
+    ax.set_ylim(-1.2, 3)
+    return ln,
+
+def update_velocity(arg):
+    print "update", arg
+    global new_velocity
+    for msg in new_velocity:
+        xdata_velocity.append(msg.header.stamp.to_sec())
+        ydata_velocity.append(msg.velocity)
+    ln.set_data(xdata, ydata)
+    new_velocity = []
+    return ln,
 
 if __name__ == '__main__':
 
     rospy.init_node("plotter")
-    rospy.Subscriber("panda_mqtt_connector/velocity", StampedVelocity, plot_x)
-    plt.ion()
+    rospy.Subscriber("panda_mqtt_connector/velocity", StampedVelocity, callback_velocity)
+    # plt.ion()
+    ani = FuncAnimation(fig, update_velocity, None, init_func=init_velocity, blit=True)
     plt.show()
+
+
     rospy.spin()
+