$search
00001 #!/usr/bin/env python 00002 # -*- coding: utf-8 -*- 00003 # 00004 # Software License Agreement (BSD License) 00005 # 00006 # Copyright (c) 2010, Antons Rebguns, Cody Jorgensen, Cara Slutter 00007 # 2010-2011, Antons Rebguns 00008 # All rights reserved. 00009 # 00010 # Redistribution and use in source and binary forms, with or without 00011 # modification, are permitted provided that the following conditions 00012 # are met: 00013 # 00014 # * Redistributions of source code must retain the above copyright 00015 # notice, this list of conditions and the following disclaimer. 00016 # * Redistributions in binary form must reproduce the above 00017 # copyright notice, this list of conditions and the following 00018 # disclaimer in the documentation and/or other materials provided 00019 # with the distribution. 00020 # * Neither the name of University of Arizona nor the names of its 00021 # contributors may be used to endorse or promote products derived 00022 # from this software without specific prior written permission. 00023 # 00024 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00025 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00026 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00027 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00028 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00029 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00030 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00031 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00032 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00033 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00034 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00035 # POSSIBILITY OF SUCH DAMAGE. 00036 00037 00038 __author__ = 'Antons Rebguns, Cody Jorgensen, Cara Slutter' 00039 __copyright__ = 'Copyright (c) 2010-2011 Antons Rebguns, Cody Jorgensen, Cara Slutter' 00040 00041 __license__ = 'BSD' 00042 __maintainer__ = 'Antons Rebguns' 00043 __email__ = 'anton@email.arizona.edu' 00044 00045 00046 from threading import Thread 00047 00048 import sys 00049 00050 import roslib 00051 roslib.load_manifest('dynamixel_controllers') 00052 00053 import rospy 00054 00055 from dynamixel_driver.dynamixel_serial_proxy import SerialProxy 00056 00057 from diagnostic_msgs.msg import DiagnosticArray 00058 from diagnostic_msgs.msg import DiagnosticStatus 00059 from diagnostic_msgs.msg import KeyValue 00060 00061 from dynamixel_controllers.srv import StartController 00062 from dynamixel_controllers.srv import StartControllerResponse 00063 from dynamixel_controllers.srv import StopController 00064 from dynamixel_controllers.srv import StopControllerResponse 00065 from dynamixel_controllers.srv import RestartController 00066 from dynamixel_controllers.srv import RestartControllerResponse 00067 00068 class ControllerManager: 00069 def __init__(self): 00070 rospy.init_node('dynamixel_controller_manager', anonymous=True) 00071 rospy.on_shutdown(self.on_shutdown) 00072 00073 self.waiting_meta_controllers = [] 00074 self.controllers = {} 00075 self.serial_proxies = {} 00076 self.diagnostics_rate = rospy.get_param('~diagnostics_rate', 1) 00077 00078 manager_namespace = rospy.get_param('~namespace') 00079 serial_ports = rospy.get_param('~serial_ports') 00080 00081 for port_namespace,port_config in serial_ports.items(): 00082 port_name = port_config['port_name'] 00083 baud_rate = port_config['baud_rate'] 00084 min_motor_id = port_config['min_motor_id'] if 'min_motor_id' in port_config else 0 00085 max_motor_id = port_config['max_motor_id'] if 'max_motor_id' in port_config else 253 00086 update_rate = port_config['update_rate'] if 'update_rate' in port_config else 5 00087 error_level_temp = 75 00088 warn_level_temp = 70 00089 00090 if 'diagnostics' in port_config: 00091 if 'error_level_temp' in port_config['diagnostics']: 00092 error_level_temp = port_config['diagnostics']['error_level_temp'] 00093 if 'warn_level_temp' in port_config['diagnostics']: 00094 warn_level_temp = port_config['diagnostics']['warn_level_temp'] 00095 00096 serial_proxy = SerialProxy(port_name, 00097 port_namespace, 00098 baud_rate, 00099 min_motor_id, 00100 max_motor_id, 00101 update_rate, 00102 self.diagnostics_rate, 00103 error_level_temp, 00104 warn_level_temp) 00105 serial_proxy.connect() 00106 00107 # will create a set of services for each serial port under common manager namesapce 00108 # e.g. /dynamixel_manager/robot_arm_port/start_controller 00109 # /dynamixel_manager/robot_head_port/start_controller 00110 # where 'dynamixel_manager' is manager's namespace 00111 # 'robot_arm_port' and 'robot_head_port' are human readable names for serial ports 00112 rospy.Service('%s/%s/start_controller' % (manager_namespace, port_namespace), StartController, self.start_controller) 00113 rospy.Service('%s/%s/stop_controller' % (manager_namespace, port_namespace), StopController, self.stop_controller) 00114 rospy.Service('%s/%s/restart_controller' % (manager_namespace, port_namespace), RestartController, self.restart_controller) 00115 00116 self.serial_proxies[port_namespace] = serial_proxy 00117 00118 # services for 'meta' controllers, e.g. joint trajectory controller 00119 # these controllers don't have their own serial port, instead they rely 00120 # on regular controllers for serial connection. The advantage of meta 00121 # controller is that it can pack commands for multiple motors on multiple 00122 # serial ports. 00123 # NOTE: all serial ports that meta controller needs should be managed by 00124 # the same controler manager. 00125 rospy.Service('%s/meta/start_controller' % manager_namespace, StartController, self.start_controller) 00126 rospy.Service('%s/meta/stop_controller' % manager_namespace, StopController, self.stop_controller) 00127 rospy.Service('%s/meta/restart_controller' % manager_namespace, RestartController, self.restart_controller) 00128 00129 self.diagnostics_pub = rospy.Publisher('/diagnostics', DiagnosticArray) 00130 if self.diagnostics_rate > 0: Thread(target=self.diagnostics_processor).start() 00131 00132 def on_shutdown(self): 00133 for serial_proxy in self.serial_proxies.values(): 00134 serial_proxy.disconnect() 00135 00136 def diagnostics_processor(self): 00137 diag_msg = DiagnosticArray() 00138 00139 rate = rospy.Rate(self.diagnostics_rate) 00140 while not rospy.is_shutdown(): 00141 diag_msg.status = [] 00142 diag_msg.header.stamp = rospy.Time.now() 00143 00144 for controller in self.controllers.values(): 00145 try: 00146 joint_state = controller.joint_state 00147 temps = joint_state.motor_temps 00148 max_temp = max(temps) 00149 00150 status = DiagnosticStatus() 00151 status.name = 'Joint Controller (%s)' % controller.joint_name 00152 status.hardware_id = 'Robotis Dynamixel %s on port %s' % (str(joint_state.motor_ids), controller.port_namespace) 00153 status.values.append(KeyValue('Goal', str(joint_state.goal_pos))) 00154 status.values.append(KeyValue('Position', str(joint_state.current_pos))) 00155 status.values.append(KeyValue('Error', str(joint_state.error))) 00156 status.values.append(KeyValue('Velocity', str(joint_state.velocity))) 00157 status.values.append(KeyValue('Load', str(joint_state.load))) 00158 status.values.append(KeyValue('Moving', str(joint_state.is_moving))) 00159 status.values.append(KeyValue('Temperature', str(max_temp))) 00160 status.level = DiagnosticStatus.OK 00161 status.message = 'OK' 00162 00163 diag_msg.status.append(status) 00164 except: 00165 pass 00166 00167 self.diagnostics_pub.publish(diag_msg) 00168 rate.sleep() 00169 00170 def check_deps(self): 00171 for controller_name,deps,kls in self.waiting_meta_controllers: 00172 if not set(deps).issubset(self.controllers.keys()): 00173 rospy.logwarn('[%s] not all dependencies started, still waiting for %s...' % (controller_name, str(list(set(deps).difference(self.controllers.keys()))))) 00174 else: 00175 dependencies = [self.controllers[dep_name] for dep_name in deps] 00176 controller = kls(controller_name, dependencies) 00177 00178 if controller.initialize(): 00179 controller.start() 00180 self.controllers[controller_name] = controller 00181 00182 self.waiting_meta_controllers = self.waiting_meta_controllers[1:] 00183 00184 def start_controller(self, req): 00185 port_name = req.port_name 00186 package_path = req.package_path 00187 module_name = req.module_name 00188 class_name = req.class_name 00189 controller_name = req.controller_name 00190 00191 if controller_name in self.controllers: 00192 return StartControllerResponse(False, 'Controller [%s] already started. If you want to restart it, call restart.' % controller_name) 00193 00194 # make sure the package_path is in PYTHONPATH 00195 if not package_path in sys.path: 00196 sys.path.append(package_path) 00197 00198 try: 00199 if module_name not in sys.modules: 00200 # import if module not previously imported 00201 controller_module = __import__(module_name) 00202 else: 00203 # reload module if previously imported 00204 controller_module = reload(sys.modules[module_name]) 00205 except ImportError, ie: 00206 return StartControllerResponse(False, 'Cannot find controller module. Unable to start controller %s\n%s' % (module_name, str(ie))) 00207 except SyntaxError, se: 00208 return StartControllerResponse(False, 'Syntax error in controller module. Unable to start controller %s\n%s' % (module_name, str(se))) 00209 except Exception, e: 00210 return StartControllerResponse(False, 'Unknown error has occured. Unable to start controller %s\n%s' % (module_name, str(e))) 00211 00212 kls = getattr(controller_module, class_name) 00213 00214 if port_name == 'meta': 00215 self.waiting_meta_controllers.append((controller_name,req.dependencies,kls)) 00216 self.check_deps() 00217 return StartControllerResponse(True, '') 00218 00219 if port_name != 'meta' and (port_name not in self.serial_proxies): 00220 return StartControllerResponse(False, 'Specified port [%s] not found, available ports are %s. Unable to start controller %s' % (port_name, str(self.serial_proxies.keys()), controller_name)) 00221 00222 controller = kls(self.serial_proxies[port_name].dxl_io, controller_name, port_name) 00223 00224 if controller.initialize(): 00225 controller.start() 00226 self.controllers[controller_name] = controller 00227 00228 self.check_deps() 00229 00230 return StartControllerResponse(True, 'Controller %s successfully started.' % controller_name) 00231 else: 00232 return StartControllerResponse(False, 'Initialization failed. Unable to start controller %s' % controller_name) 00233 00234 def stop_controller(self, req): 00235 controller_name = req.controller_name 00236 00237 if controller_name in self.controllers: 00238 self.controllers[controller_name].stop() 00239 del self.controllers[controller_name] 00240 return StopControllerResponse(True, 'controller %s successfully stopped.' % controller_name) 00241 else: 00242 return StopControllerResponse(False, 'controller %s was not running.' % controller_name) 00243 00244 def restart_controller(self, req): 00245 response1 = self.stop_controller(StopController(req.controller_name)) 00246 response2 = self.start_controller(req) 00247 return RestartControllerResponse(response1.success and response2.success, '%s\n%s' % (response1.reason, response2.reason)) 00248 00249 if __name__ == '__main__': 00250 try: 00251 manager = ControllerManager() 00252 rospy.spin() 00253 except rospy.ROSInterruptException: pass 00254