$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2011, Willow Garage, Inc. 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions 00008 # are met: 00009 # 00010 # * Redistributions of source code must retain the above copyright 00011 # notice, this list of conditions and the following disclaimer. 00012 # * Redistributions in binary form must reproduce the above 00013 # copyright notice, this list of conditions and the following 00014 # disclaimer in the documentation and/or other materials provided 00015 # with the distribution. 00016 # * Neither the name of Willow Garage, Inc. nor the names of its 00017 # contributors may be used to endorse or promote products derived 00018 # from this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 00032 # 00033 # Revision $Id: app_manager.py 14948 2011-09-07 19:25:54Z pratkanis $ 00034 00035 # author: leibs 00036 00037 import roslib.names 00038 import rospy 00039 import thread 00040 import time 00041 00042 import roslaunch.parent 00043 import roslaunch.pmon 00044 00045 from .app import AppDefinition, load_AppDefinition_by_name 00046 from .exceptions import LaunchException, AppException, InvalidAppException, NotFoundException 00047 from .master_sync import MasterSync 00048 from .msg import App, AppList, StatusCodes, AppStatus, AppInstallationState, ExchangeApp 00049 from .srv import StartApp, StopApp, ListApps, ListAppsResponse, StartAppResponse, StopAppResponse, InstallApp, UninstallApp, GetInstallationState, UninstallAppResponse, InstallAppResponse, GetInstallationStateResponse, GetAppDetails, GetAppDetailsResponse 00050 00051 class AppManager(object): 00052 00053 def __init__(self, robot_name, interface_master, app_list, exchange): 00054 self._robot_name = robot_name 00055 self._interface_master = interface_master 00056 self._app_list = app_list 00057 self._current_app = self._current_app_definition = None 00058 self._exchange = exchange 00059 00060 rospy.loginfo("Starting app manager for %s"%self._robot_name) 00061 00062 self._app_interface = self.scoped_name('application') 00063 00064 # note: we publish into the application namespace 00065 self._status_pub = rospy.Publisher(self.scoped_name('application/app_status'), AppStatus, latch=True) 00066 self._list_apps_pub = rospy.Publisher(self.scoped_name('app_list'), AppList, latch=True) 00067 00068 self._list_apps_srv = rospy.Service(self.scoped_name('list_apps'), ListApps, self.handle_list_apps) 00069 self._start_app_srv = rospy.Service(self.scoped_name('start_app'), StartApp, self.handle_start_app) 00070 self._stop_app_srv = rospy.Service(self.scoped_name('stop_app'), StopApp, self.handle_stop_app) 00071 if (self._exchange): 00072 self._exchange_list_apps_pub = rospy.Publisher(self.scoped_name('exchange_app_list'), AppInstallationState, latch=True) 00073 self._list_exchange_apps_srv = rospy.Service(self.scoped_name('list_exchange_apps'), GetInstallationState, self.handle_list_exchange_apps) 00074 self._get_app_details_srv = rospy.Service(self.scoped_name('get_app_details'), GetAppDetails, self.handle_get_app_details) 00075 self._install_app_srv = rospy.Service(self.scoped_name('install_app'), InstallApp, self.handle_install_app) 00076 self._uninstall_app_srv = rospy.Service(self.scoped_name('uninstall_app'), UninstallApp, self.handle_uninstall_app) 00077 00078 pub_names = [x.resolved_name for x in [self._list_apps_pub, self._status_pub, self._exchange_list_apps_pub]] 00079 service_names = [x.resolved_name for x in [self._list_apps_srv, self._start_app_srv, self._stop_app_srv, self._get_app_details_srv, self._list_exchange_apps_srv, self._install_app_srv, self._uninstall_app_srv]] 00080 else: 00081 pub_names = [x.resolved_name for x in [self._list_apps_pub, self._status_pub]] 00082 service_names = [x.resolved_name for x in [self._list_apps_srv, self._start_app_srv, self._stop_app_srv]] 00083 00084 self._api_sync = MasterSync(self._interface_master, 00085 local_service_names=service_names, 00086 local_pub_names=pub_names) 00087 00088 self._launch = None 00089 self._interface_sync = None 00090 00091 roslaunch.pmon._init_signal_handlers() 00092 00093 if (self._exchange): 00094 self._exchange.update_local() 00095 00096 self._app_list.update() 00097 self.publish_exchange_list_apps() 00098 self.publish_list_apps() 00099 00100 def shutdown(self): 00101 if self._api_sync: 00102 self._api_sync.stop() 00103 if self._launch: 00104 self._launch.shutdown() 00105 self._interface_sync.stop() 00106 00107 def _get_current_app(self): 00108 return self._current_app 00109 00110 def _set_current_app(self, app, app_definition): 00111 self._current_app = app 00112 self._current_app_definition = app_definition 00113 00114 if self._list_apps_pub: 00115 if app is not None: 00116 self._list_apps_pub.publish([app], self._app_list.get_app_list()) 00117 else: 00118 self._list_apps_pub.publish([], self._app_list.get_app_list()) 00119 00120 def scoped_name(self, name): 00121 return roslib.names.canonicalize_name('/%s/%s'%(self._robot_name, rospy.remap_name(name))) 00122 00123 def handle_get_app_details(self, req): 00124 return GetAppDetailsResponse(app=self._exchange.get_app_details(req.name)) 00125 00126 def handle_list_exchange_apps(self, req): 00127 if (self._exchange == None): 00128 return None 00129 if (req.remote_update): 00130 print "UPDATE" 00131 if (not self._exchange.update()): 00132 return None 00133 i_apps = self._exchange.get_installed_apps() 00134 a_apps = self._exchange.get_available_apps() 00135 return GetInstallationStateResponse(installed_apps=i_apps, available_apps=a_apps) 00136 00137 def publish_list_apps(self): 00138 if self._current_app: 00139 self._list_apps_pub.publish([self._current_app], self._app_list.get_app_list()) 00140 else: 00141 self._list_apps_pub.publish([], self._app_list.get_app_list()) 00142 00143 def publish_exchange_list_apps(self): 00144 if (self._exchange == None): 00145 return 00146 i_apps = self._exchange.get_installed_apps() 00147 a_apps = self._exchange.get_available_apps() 00148 self._exchange_list_apps_pub.publish(i_apps, a_apps) 00149 00150 def handle_install_app(self, req): 00151 appname = req.name 00152 if (self._exchange.install_app(appname)): 00153 self._app_list.update() 00154 self.publish_list_apps() 00155 self.publish_exchange_list_apps() 00156 return InstallAppResponse(installed=True, message="app [%s] installed"%(appname)) 00157 else: 00158 return InstallAppResponse(installed=False, message="app [%s] could not be installed"%(appname)) 00159 00160 def handle_uninstall_app(self, req): 00161 appname = req.name 00162 if (self._exchange.uninstall_app(appname)): 00163 self._app_list.update() 00164 self.publish_list_apps() 00165 self.publish_exchange_list_apps() 00166 return UninstallAppResponse(uninstalled=True, message="app [%s] uninstalled"%(appname)) 00167 else: 00168 return UninstallAppResponse(uninstalled=False, message="app [%s] could not be uninstalled"%(appname)) 00169 00170 def handle_list_apps(self, req): 00171 rospy.loginfo("Listing apps") 00172 current = self._current_app 00173 if current: 00174 running_apps = [current] 00175 else: 00176 running_apps = [] 00177 self._app_list.update() 00178 rospy.loginfo("done listing apps") 00179 return ListAppsResponse(running_apps=running_apps, available_apps=self._app_list.get_app_list()) 00180 00181 def handle_start_app(self, req): 00182 rospy.loginfo("start_app: %s"%(req.name)) 00183 if self._current_app: 00184 if self._current_app_definition.name == req.name: 00185 return StartAppResponse(started=True, message="app [%s] already started"%(req.name), namespace=self._app_interface) 00186 else: 00187 self.stop_app(self._current_app_definition.name) 00188 #return StartAppResponse(started=False, message="Please stop the running app before starting another app.", error_code=StatusCodes.MULTIAPP_NOT_SUPPORTED) 00189 00190 # TODO: the app list has already loaded the App data. We should use that instead for consistency 00191 00192 appname = req.name 00193 rospy.loginfo("Loading app: %s"%(appname)) 00194 try: 00195 app = load_AppDefinition_by_name(appname) 00196 except ValueError as e: 00197 return StartAppResponse(started=False, message=str(e), error_code=StatusCodes.BAD_REQUEST) 00198 except InvalidAppException as e: 00199 return StartAppResponse(started=False, message=str(e), error_code=StatusCodes.INTERNAL_ERROR) 00200 except NotFoundException as e: 00201 return StartAppResponse(started=False, message=str(e), error_code=StatusCodes.NOT_FOUND) 00202 00203 try: 00204 self._set_current_app(App(name=appname), app) 00205 00206 rospy.loginfo("Launching: %s"%(app.launch)) 00207 self._status_pub.publish(AppStatus(AppStatus.INFO, 'launching %s'%(app.display_name))) 00208 00209 #TODO:XXX This is a roslaunch-caller-like abomination. Should leverage a true roslaunch API when it exists. 00210 self._launch = roslaunch.parent.ROSLaunchParent(rospy.get_param("/run_id"), 00211 [app.launch], is_core=False, 00212 process_listeners=()) 00213 self._launch._load_config() 00214 00215 #TODO: convert to method 00216 for N in self._launch.config.nodes: 00217 for t in app.interface.published_topics.keys(): 00218 N.remap_args.append((t, self._app_interface + '/' + t)) 00219 for t in app.interface.subscribed_topics.keys(): 00220 N.remap_args.append((t, self._app_interface + '/' + t)) 00221 self._launch.start() 00222 00223 fp = [self._app_interface + '/' + x for x in app.interface.subscribed_topics.keys()] 00224 lp = [self._app_interface + '/' + x for x in app.interface.published_topics.keys()] 00225 00226 self._interface_sync = MasterSync(self._interface_master, foreign_pub_names=fp, local_pub_names=lp) 00227 00228 thread.start_new_thread(self.app_monitor,()) 00229 00230 return StartAppResponse(started=True, message="app [%s] started"%(appname), namespace=self._app_interface) 00231 00232 except Exception as e: 00233 try: 00234 # attempt to kill any launched resources 00235 self._stop_current() 00236 except: 00237 pass 00238 self._status_pub.publish(AppStatus(AppStatus.INFO, 'app start failed')) 00239 rospy.logerr("app start failed") 00240 return StartAppResponse(started=False, message="internal error [%s]"%(str(e)), error_code=StatusCodes.INTERNAL_ERROR) 00241 00242 def _stop_current(self): 00243 try: 00244 self._launch.shutdown() 00245 finally: 00246 self._launch = None 00247 try: 00248 self._interface_sync.stop() 00249 finally: 00250 self._interface_sync = None 00251 00252 def handle_stop_app(self, req): 00253 rospy.loginfo("handle stop app: %s"%(req.name)) 00254 return self.stop_app(req.name) 00255 00256 def app_monitor(self): 00257 while self._launch: 00258 time.sleep(0.1) 00259 launch = self._launch 00260 if launch: 00261 pm = launch.pm 00262 if pm: 00263 if pm.done: 00264 time.sleep(1.0) 00265 self.stop_app(self._current_app_definition.name) 00266 break 00267 00268 00269 00270 def stop_app(self, appname): 00271 resp = StopAppResponse(stopped=False) 00272 try: 00273 app = self._current_app_definition 00274 00275 # request to stop all apps. 00276 if app is not None and appname == '*': 00277 appname = app.name 00278 00279 if app is None or app.name != appname: 00280 rospy.loginfo("handle stop app: app [%s] is not running [x]"%(appname)) 00281 resp.error_code = StatusCodes.NOT_RUNNING 00282 resp.message = "app %s is not running"%(appname) 00283 else: 00284 try: 00285 if self._launch: 00286 rospy.loginfo("handle stop app: stopping app [%s]"%(appname)) 00287 self._status_pub.publish(AppStatus(AppStatus.INFO, 'stopping %s'%(app.display_name))) 00288 self._stop_current() 00289 rospy.loginfo("handle stop app: app [%s] stopped"%(appname)) 00290 resp.stopped = True 00291 resp.message = "%s stopped"%(appname) 00292 else: 00293 rospy.loginfo("handle stop app: app [%s] is not running"%(appname)) 00294 resp.message = "app [%s] is not running"%(appname) 00295 resp.error_code = StatusCodes.NOT_RUNNING 00296 finally: 00297 self._launch = None 00298 self._set_current_app(None, None) 00299 00300 except Exception as e: 00301 rospy.logerr("handle stop app: internal error %s"%(e)) 00302 resp.error_code = StatusCodes.INTERNAL_ERROR 00303 resp.message = "internal error: %s"%(str(e)) 00304 00305 return resp