diff --git a/ros_ethercat_model/src/ros_ethercat_model/calibrate_class.py b/ros_ethercat_model/src/ros_ethercat_model/calibrate_class.py index 74c5f75..d50f037 100644 --- a/ros_ethercat_model/src/ros_ethercat_model/calibrate_class.py +++ b/ros_ethercat_model/src/ros_ethercat_model/calibrate_class.py @@ -61,7 +61,7 @@ def calibrate(self, controllers): print("Launched: %s" % ', '.join(launched)) # Starts the launched controllers - self.switch_controller(launched, [], controller_manager_srvs.SwitchControllerRequest.BEST_EFFORT) + self.switch_controller(launched, [], controller_manager_srvs.SwitchControllerRequest.BEST_EFFORT, False, 0) # Sets up callbacks for calibration completion waiting_for = launched[:] @@ -80,7 +80,7 @@ def calibrated(msg, name): # Somewhat not thread-safe for name in launched: try: resp_stop = self.switch_controller([], [name], - controller_manager_srvs.SwitchControllerRequest.STRICT) + controller_manager_srvs.SwitchControllerRequest.STRICT, False, 0) if (resp_stop == 0): rospy.logerr("Failed to stop controller %s" % name) resp_unload = self.unload_controller(name)