pr2_controller_manager_interface.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 # Wrappers around the services provided by MechanismControlNode
00003 
00004 import roslib; roslib.load_manifest('pr2_controller_manager')
00005 
00006 import sys
00007 
00008 import rospy
00009 from pr2_mechanism_msgs.srv import *
00010 
00011 def list_controller_types():
00012     rospy.wait_for_service('pr2_controller_manager/list_controller_types')
00013     s = rospy.ServiceProxy('pr2_controller_manager/list_controller_types', ListControllerTypes)
00014     resp = s.call(ListControllerTypesRequest())
00015     for t in resp.types:
00016         print t
00017 
00018 def reload_libraries(force_kill, restore = False):
00019     rospy.wait_for_service('pr2_controller_manager/reload_controller_libraries')
00020     s = rospy.ServiceProxy('pr2_controller_manager/reload_controller_libraries', ReloadControllerLibraries)
00021 
00022     list_srv = rospy.ServiceProxy('pr2_controller_manager/list_controllers', ListControllers)
00023     load_srv = rospy.ServiceProxy('pr2_controller_manager/load_controller', LoadController)
00024     switch_srv = rospy.ServiceProxy('pr2_controller_manager/switch_controller', SwitchController)
00025 
00026     print "Restore:", restore
00027     if restore:
00028         originally = list_srv.call(ListControllersRequest())
00029     
00030     resp = s.call(ReloadControllerLibrariesRequest(force_kill))
00031     if resp.ok:
00032         print "Successfully reloaded libraries"
00033         result = True
00034     else:
00035         print "Failed to reload libraries. Do you still have controllers loaded?"
00036         result = False
00037 
00038     if restore:
00039         for c in originally.controllers:
00040             load_srv(c)
00041         to_start = []
00042         for c, s in zip(originally.controllers, originally.state):
00043             if s == 'running':
00044                 to_start.append(c)
00045         switch_srv(start_controllers = to_start,
00046                    stop_controllers = [],
00047                    strictness = SwitchControllerRequest.BEST_EFFORT)
00048         print "Controllers restored to original state"
00049     return result
00050         
00051 
00052 def list_controllers():
00053     rospy.wait_for_service('pr2_controller_manager/list_controllers')
00054     s = rospy.ServiceProxy('pr2_controller_manager/list_controllers', ListControllers)
00055     resp = s.call(ListControllersRequest())
00056     if len(resp.controllers) == 0:
00057         print "No controllers are loaded in mechanism control"
00058     else:
00059         for c, s in zip(resp.controllers, resp.state):
00060             print c, "(",s,")"
00061 
00062 def load_controller(name):
00063     rospy.wait_for_service('pr2_controller_manager/load_controller')
00064     s = rospy.ServiceProxy('pr2_controller_manager/load_controller', LoadController)
00065     resp = s.call(LoadControllerRequest(name))
00066     if resp.ok:
00067         print "Loaded", name
00068         return True
00069     else:
00070         print "Error when loading", name
00071         return False
00072 
00073 def unload_controller(name):
00074     rospy.wait_for_service('pr2_controller_manager/unload_controller')
00075     s = rospy.ServiceProxy('pr2_controller_manager/unload_controller', UnloadController)
00076     resp = s.call(UnloadControllerRequest(name))
00077     if resp.ok == 1:
00078         print "Unloaded %s successfully" % name
00079         return True
00080     else:
00081         print "Error when unloading", name
00082         return False
00083 
00084 def start_controller(name):
00085     return start_stop_controllers([name], True)
00086 
00087 def start_controllers(names):
00088     return start_stop_controllers(names, True)
00089 
00090 def stop_controller(name):
00091     return start_stop_controllers([name], False)
00092 
00093 def stop_controllers(names):
00094     return start_stop_controllers(name, False)
00095 
00096 def start_stop_controllers(names, st):
00097     rospy.wait_for_service('pr2_controller_manager/switch_controller')
00098     s = rospy.ServiceProxy('pr2_controller_manager/switch_controller', SwitchController)
00099     start = []
00100     stop = []
00101     strictness = SwitchControllerRequest.STRICT
00102     if st:
00103         start = names
00104     else:
00105         stop = names
00106     resp = s.call(SwitchControllerRequest(start, stop, strictness))
00107     if resp.ok == 1:
00108         if st:
00109             print "Started %s successfully" % names
00110         else:
00111             print "Stopped %s successfully" % names
00112         return True
00113     else:
00114         if st:
00115             print "Error when starting ", names
00116         else:
00117             print "Error when stopping ", names
00118         return False


pr2_controller_manager
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Mon Dec 2 2013 13:13:13