2121# Loads interface with the robot.
2222import rospy
2323import controller_manager_msgs .srv as controller_manager_srvs
24+ from controller_manager_msgs .srv import SwitchControllerRequest
2425from std_msgs .msg import Bool , Empty
2526
2627
@@ -49,6 +50,7 @@ def calibrate(self, controllers):
4950 controllers = [controllers ]
5051
5152 launched = []
53+ req = SwitchControllerRequest ()
5254 try :
5355 # Loads the controllers
5456 for c in controllers :
@@ -61,7 +63,13 @@ def calibrate(self, controllers):
6163 print ("Launched: %s" % ', ' .join (launched ))
6264
6365 # Starts the launched controllers
64- self .switch_controller (launched , [], controller_manager_srvs .SwitchControllerRequest .BEST_EFFORT , False , 0 )
66+
67+ req .start_controllers = launched
68+ req .stop_controllers = []
69+ req .strictness = SwitchControllerRequest .BEST_EFFORT
70+ req .start_asap = False
71+ req .timeout = 0.0
72+ self .switch_controller .call (req )
6573
6674 # Sets up callbacks for calibration completion
6775 waiting_for = launched [:]
@@ -79,8 +87,12 @@ def calibrated(msg, name): # Somewhat not thread-safe
7987 finally :
8088 for name in launched :
8189 try :
82- resp_stop = self .switch_controller ([], [name ],
83- controller_manager_srvs .SwitchControllerRequest .STRICT , False , 0 )
90+ req .start_controllers = []
91+ req .stop_controllers = [name ]
92+ req .strictness = SwitchControllerRequest .STRICT
93+ req .start_asap = False
94+ req .timeout = 0.0
95+ resp_stop = self .switch_controller .call (req )
8496 if (resp_stop == 0 ):
8597 rospy .logerr ("Failed to stop controller %s" % name )
8698 resp_unload = self .unload_controller (name )
0 commit comments