Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 import rospy
00021 from time import sleep
00022
00023 from controller_manager_msgs.srv import LoadController, ListControllers, SwitchController, SwitchControllerRequest
00024
00025
00026 class LoadPassthroughControllers(object):
00027 """
00028 Load the passthrough controllers for all the RoNeXes present on the bus.
00029 """
00030
00031 def __init__(self):
00032 """
00033 """
00034 ronex_ids = self.find_ronexes()
00035
00036 if len(ronex_ids) > 0:
00037 self.set_param(ronex_ids)
00038 self.load_and_start_ctrl(ronex_ids)
00039
00040 def find_ronexes(self):
00041 """
00042 Find the ronexes present on the system
00043
00044 @return a list of ronex_ids
00045 """
00046 ronex_ids = []
00047
00048
00049
00050 attempts = 50
00051 rospy.loginfo("Waiting for the ronex to be loaded properly.")
00052 while attempts and not rospy.has_param("/ronex/devices/0/ronex_id"):
00053 sleep(0.1)
00054 attempts -= 1
00055
00056 if attempts > 0:
00057 ronex_param = rospy.get_param("/ronex/devices")
00058 for key in ronex_param:
00059 ronex_ids.append([ronex_param[key]["ronex_id"], ronex_param[key]["product_name"]])
00060 else:
00061 rospy.loginfo("Failed to find ronex devices in parameter server")
00062
00063 return ronex_ids
00064
00065 def set_param(self, ronex_ids):
00066 """
00067 Load the parameters for the present ronexes into the parameter server
00068
00069 @param ronex_ids the ids of the ronexes
00070 """
00071 for ronex_id in ronex_ids:
00072 if ronex_id[1] == "general_io":
00073 rospy.set_param("/ronex_" + ronex_id[0] + "_passthrough/type",
00074 "sr_ronex_controllers/GeneralIOPassthroughController")
00075 rospy.set_param("/ronex_" + ronex_id[0] + "_passthrough/ronex_id", ronex_id[0])
00076 elif ronex_id[1] == "spi":
00077 rospy.set_param("/ronex_" + ronex_id[0] + "_passthrough/type",
00078 "sr_ronex_controllers/SPIPassthroughController")
00079 rospy.set_param("/ronex_" + ronex_id[0] + "_passthrough/ronex_id", ronex_id[0])
00080 elif ronex_id[1] == "adc16":
00081 rospy.set_param("/ronex_" + ronex_id[0] + "_passthrough/type",
00082 "sr_ronex_controllers/ADC16PassthroughController")
00083 rospy.set_param("/ronex_" + ronex_id[0] + "_passthrough/ronex_id", ronex_id[0])
00084 elif ronex_id[1] == "DC_MOTOR_SMALL":
00085 rospy.set_param("/ronex_" + ronex_id[0] + "_passthrough/type",
00086 "sr_ronex_controllers/DCMotorSmallPassthroughController")
00087 rospy.set_param("/ronex_" + ronex_id[0] + "_passthrough/ronex_id", ronex_id[0])
00088 else:
00089 rospy.logwarn("RoNeX["+ronex_id[0]+"] type not recognized: "+ronex_id[1] +
00090 " -> not loading any controllers for that RoNeX")
00091
00092 def load_and_start_ctrl(self, ronex_ids):
00093 """
00094 Load and start the passthrough controllers for the list of given ronexes.
00095
00096 @param ronex_ids the ids of the ronexes
00097 """
00098
00099 controllers_list = []
00100 for ronex_id in ronex_ids:
00101 controllers_list.append("ronex_" + ronex_id[0] + "_passthrough")
00102
00103
00104 rospy.loginfo("Waiting for controller_manager services: list/load/switch")
00105 rospy.wait_for_service('controller_manager/list_controllers')
00106 rospy.wait_for_service('controller_manager/load_controller')
00107 rospy.wait_for_service('controller_manager/switch_controller')
00108
00109 list_controllers = rospy.ServiceProxy('controller_manager/list_controllers', ListControllers)
00110 load_controller = rospy.ServiceProxy('controller_manager/load_controller', LoadController)
00111 switch_controller = rospy.ServiceProxy('controller_manager/switch_controller', SwitchController)
00112
00113 rospy.loginfo("Starting controllers: " + str(controllers_list))
00114
00115
00116 available_controllers = None
00117 try:
00118 available_controllers = list_controllers()
00119 except rospy.ServiceException, e:
00120 print "Service did not process request: %s" % str(e)
00121
00122
00123 for ctrl in controllers_list:
00124 if ctrl not in available_controllers.controller:
00125 try:
00126 resp1 = load_controller(ctrl)
00127 except rospy.ServiceException, e:
00128 print "Service did not process request: %s" % str(e)
00129
00130
00131 try:
00132 resp1 = switch_controller(controllers_list, [], SwitchControllerRequest.BEST_EFFORT)
00133 except rospy.ServiceException, e:
00134 print "Service did not process request: %s" % str(e)
00135
00136
00137 if __name__ == "__main__":
00138 rospy.sleep(2.5)
00139 rospy.init_node("load_passthrough_controllers")
00140 load_passthrough = LoadPassthroughControllers()