Skip to content
Snippets Groups Projects
Commit 028bd256 authored by Francois Keith's avatar Francois Keith
Browse files

Adapt run_command to the extraction of the messages from dynamic_graph_bridge.

parent cc2df49f
No related branches found
No related tags found
No related merge requests found
...@@ -3,7 +3,7 @@ ...@@ -3,7 +3,7 @@
import roslib; roslib.load_manifest('dynamic_graph_bridge') import roslib; roslib.load_manifest('dynamic_graph_bridge')
import rospy import rospy
import dynamic_graph_bridge.srv import dynamic_graph_bridge_msgs.srv
import sys import sys
import code import code
...@@ -18,7 +18,7 @@ class RosShell(InteractiveConsole): ...@@ -18,7 +18,7 @@ class RosShell(InteractiveConsole):
rospy.loginfo('waiting for service...') rospy.loginfo('waiting for service...')
rospy.wait_for_service('run_command') rospy.wait_for_service('run_command')
self.client = rospy.ServiceProxy( 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): def runcode(self, code, retry = True):
...@@ -29,7 +29,7 @@ class RosShell(InteractiveConsole): ...@@ -29,7 +29,7 @@ class RosShell(InteractiveConsole):
if not self.client: if not self.client:
print("Connection to remote server lost. Reconnecting...") print("Connection to remote server lost. Reconnecting...")
self.client = rospy.ServiceProxy( self.client = rospy.ServiceProxy(
'run_command', dynamic_graph_bridge.srv.RunCommand, True) 'run_command', dynamic_graph_bridge_msgs.srv.RunCommand, True)
if retry: if retry:
print("Retrying previous command...") print("Retrying previous command...")
self.cache = source self.cache = source
...@@ -44,7 +44,7 @@ class RosShell(InteractiveConsole): ...@@ -44,7 +44,7 @@ class RosShell(InteractiveConsole):
except rospy.ServiceException, e: except rospy.ServiceException, e:
print("Connection to remote server lost. Reconnecting...") print("Connection to remote server lost. Reconnecting...")
self.client = rospy.ServiceProxy( self.client = rospy.ServiceProxy(
'run_command', dynamic_graph_bridge.srv.RunCommand, True) 'run_command', dynamic_graph_bridge_msgs.srv.RunCommand, True)
if retry: if retry:
print("Retrying previous command...") print("Retrying previous command...")
self.cache = source self.cache = source
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment