diff --git a/scripts/run_command b/scripts/run_command
index 0d05a4de0fda95dbbe6722e7e4819f191da4454a..f06cf1cf261f0b951a612011897b56e3201055dd 100755
--- a/scripts/run_command
+++ b/scripts/run_command
@@ -3,7 +3,7 @@
 import roslib; roslib.load_manifest('dynamic_graph_bridge')
 import rospy
 
-import dynamic_graph_bridge.srv
+import dynamic_graph_bridge_msgs.srv
 
 import sys
 import code
@@ -18,7 +18,7 @@ class RosShell(InteractiveConsole):
         rospy.loginfo('waiting for service...')
         rospy.wait_for_service('run_command')
         self.client = rospy.ServiceProxy(
-            'run_command', dynamic_graph_bridge.srv.RunCommand, True)
+            'run_command', dynamic_graph_bridge_msgs.srv.RunCommand, True)
 
 
     def runcode(self, code, retry = True):
@@ -29,7 +29,7 @@ class RosShell(InteractiveConsole):
                 if not self.client:
                     print("Connection to remote server lost. Reconnecting...")
                     self.client = rospy.ServiceProxy(
-                        'run_command', dynamic_graph_bridge.srv.RunCommand, True)
+                        'run_command', dynamic_graph_bridge_msgs.srv.RunCommand, True)
                     if retry:
                         print("Retrying previous command...")
                         self.cache = source
@@ -44,7 +44,7 @@ class RosShell(InteractiveConsole):
             except rospy.ServiceException, e:
                 print("Connection to remote server lost. Reconnecting...")
                 self.client = rospy.ServiceProxy(
-                    'run_command', dynamic_graph_bridge.srv.RunCommand, True)
+                    'run_command', dynamic_graph_bridge_msgs.srv.RunCommand, True)
                 if retry:
                     print("Retrying previous command...")
                     self.cache = source