Skip to content

Commit

Permalink
Use a SwitchControllerRequest object instead of python mapping to the…
Browse files Browse the repository at this point in the history
… request, to be compatible with future API changes
  • Loading branch information
guihomework committed Feb 14, 2020
1 parent dbf667c commit ef80287
Showing 1 changed file with 15 additions and 3 deletions.
18 changes: 15 additions & 3 deletions ros_ethercat_model/src/ros_ethercat_model/calibrate_class.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
# Loads interface with the robot.
import rospy
import controller_manager_msgs.srv as controller_manager_srvs
from controller_manager_msgs.srv import SwitchControllerRequest
from std_msgs.msg import Bool, Empty


Expand Down Expand Up @@ -49,6 +50,7 @@ def calibrate(self, controllers):
controllers = [controllers]

launched = []
req = SwitchControllerRequest()
try:
# Loads the controllers
for c in controllers:
Expand All @@ -61,7 +63,13 @@ def calibrate(self, controllers):
print("Launched: %s" % ', '.join(launched))

# Starts the launched controllers
self.switch_controller(launched, [], controller_manager_srvs.SwitchControllerRequest.BEST_EFFORT, False, 0)

req.start_controllers = launched
req.stop_controllers = []
req.strictness = SwitchControllerRequest.BEST_EFFORT
req.start_asap = False
req.timeout = 0.0
self.switch_controller.call(req)

# Sets up callbacks for calibration completion
waiting_for = launched[:]
Expand All @@ -79,8 +87,12 @@ def calibrated(msg, name): # Somewhat not thread-safe
finally:
for name in launched:
try:
resp_stop = self.switch_controller([], [name],
controller_manager_srvs.SwitchControllerRequest.STRICT, False, 0)
req.start_controllers = []
req.stop_controllers = [name]
req.strictness = SwitchControllerRequest.STRICT
req.start_asap = False
req.timeout = 0.0
resp_stop = self.switch_controller.call(req)
if (resp_stop == 0):
rospy.logerr("Failed to stop controller %s" % name)
resp_unload = self.unload_controller(name)
Expand Down

0 comments on commit ef80287

Please sign in to comment.