00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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, single_app):
00054 self._robot_name = robot_name
00055 self._interface_master = interface_master
00056 self._app_list = app_list
00057 self._single_app = single_app
00058 self._current_apps = []
00059 self._current_app_definitions = []
00060 self._exchange = exchange
00061
00062 rospy.loginfo("Starting app manager for %s"%self._robot_name)
00063
00064 self._app_interface = self.scoped_name('application')
00065
00066
00067 self._status_pub = rospy.Publisher(self.scoped_name('application/app_status'), AppStatus, latch=True)
00068 self._list_apps_pub = rospy.Publisher(self.scoped_name('app_list'), AppList, latch=True)
00069
00070 self._list_apps_srv = rospy.Service(self.scoped_name('list_apps'), ListApps, self.handle_list_apps)
00071 self._start_app_srv = rospy.Service(self.scoped_name('start_app'), StartApp, self.handle_start_app)
00072 self._stop_app_srv = rospy.Service(self.scoped_name('stop_app'), StopApp, self.handle_stop_app)
00073 if (self._exchange):
00074 self._exchange_list_apps_pub = rospy.Publisher(self.scoped_name('exchange_app_list'), AppInstallationState, latch=True)
00075 self._list_exchange_apps_srv = rospy.Service(self.scoped_name('list_exchange_apps'), GetInstallationState, self.handle_list_exchange_apps)
00076 self._get_app_details_srv = rospy.Service(self.scoped_name('get_app_details'), GetAppDetails, self.handle_get_app_details)
00077 self._install_app_srv = rospy.Service(self.scoped_name('install_app'), InstallApp, self.handle_install_app)
00078 self._uninstall_app_srv = rospy.Service(self.scoped_name('uninstall_app'), UninstallApp, self.handle_uninstall_app)
00079
00080 pub_names = [x.resolved_name for x in [self._list_apps_pub, self._status_pub, self._exchange_list_apps_pub]]
00081 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]]
00082 else:
00083 pub_names = [x.resolved_name for x in [self._list_apps_pub, self._status_pub]]
00084 service_names = [x.resolved_name for x in [self._list_apps_srv, self._start_app_srv, self._stop_app_srv]]
00085
00086 self._api_sync = MasterSync(self._interface_master,
00087 local_service_names=service_names,
00088 local_pub_names=pub_names)
00089
00090 self._launch = None
00091 self._launches = {}
00092 self._interface_sync = None
00093
00094 roslaunch.pmon._init_signal_handlers()
00095
00096 if (self._exchange):
00097 self._exchange.update_local()
00098
00099 self._app_list.update()
00100 self.publish_exchange_list_apps()
00101 self.publish_list_apps()
00102
00103 def shutdown(self):
00104 if self._api_sync:
00105 self._api_sync.stop()
00106 if self._launch:
00107 self._launch.shutdown()
00108 self._interface_sync.stop()
00109
00110 def _set_current_apps(self, apps, app_definitions):
00111 self._current_apps = apps
00112 self._current_app_definitions = app_definitions
00113
00114 if self._list_apps_pub:
00115 self._list_apps_pub.publish(apps, self._app_list.get_app_list())
00116
00117 def scoped_name(self, name):
00118 return roslib.names.canonicalize_name('/%s/%s'%(self._robot_name, rospy.remap_name(name)))
00119
00120 def handle_get_app_details(self, req):
00121 return GetAppDetailsResponse(app=self._exchange.get_app_details(req.name))
00122
00123 def handle_list_exchange_apps(self, req):
00124 if (self._exchange == None):
00125 return None
00126 if (req.remote_update):
00127 print "UPDATE"
00128 if (not self._exchange.update()):
00129 return None
00130 i_apps = self._exchange.get_installed_apps()
00131 a_apps = self._exchange.get_available_apps()
00132 return GetInstallationStateResponse(installed_apps=i_apps, available_apps=a_apps)
00133
00134 def publish_list_apps(self):
00135 self._list_apps_pub.publish(self._current_apps, self._app_list.get_app_list())
00136
00137 def publish_exchange_list_apps(self):
00138 if (self._exchange == None):
00139 return
00140 i_apps = self._exchange.get_installed_apps()
00141 a_apps = self._exchange.get_available_apps()
00142 self._exchange_list_apps_pub.publish(i_apps, a_apps)
00143
00144 def handle_install_app(self, req):
00145 appname = req.name
00146 if (self._exchange.install_app(appname)):
00147 self._app_list.update()
00148 self.publish_list_apps()
00149 self.publish_exchange_list_apps()
00150 return InstallAppResponse(installed=True, message="app [%s] installed"%(appname))
00151 else:
00152 return InstallAppResponse(installed=False, message="app [%s] could not be installed"%(appname))
00153
00154 def handle_uninstall_app(self, req):
00155 appname = req.name
00156 if (self._exchange.uninstall_app(appname)):
00157 self._app_list.update()
00158 self.publish_list_apps()
00159 self.publish_exchange_list_apps()
00160 return UninstallAppResponse(uninstalled=True, message="app [%s] uninstalled"%(appname))
00161 else:
00162 return UninstallAppResponse(uninstalled=False, message="app [%s] could not be uninstalled"%(appname))
00163
00164 def handle_list_apps(self, req):
00165 rospy.loginfo("Listing apps")
00166 current = self._current_apps
00167 running_apps = current
00168 self._app_list.update()
00169 rospy.loginfo("done listing apps")
00170 return ListAppsResponse(running_apps=running_apps, available_apps=self._app_list.get_app_list())
00171
00172 def handle_start_app(self, req):
00173 rospy.loginfo("start_app: %s"%(req.name))
00174 if len(self._current_apps) > 0:
00175 for app in self._current_app_definitions:
00176 if app.name == req.name:
00177 return StartAppResponse(started=True, message="app [%s] already started"%(req.name), namespace=self._app_interface)
00178 elif (self._single_app):
00179 return StartAppResponse(started=False, message="Please stop the running app before starting another app.", error_code=StatusCodes.MULTIAPP_NOT_SUPPORTED)
00180
00181
00182
00183 appname = req.name
00184 rospy.loginfo("Loading app: %s"%(appname))
00185 try:
00186 app = load_AppDefinition_by_name(appname)
00187 except ValueError as e:
00188 return StartAppResponse(started=False, message=str(e), error_code=StatusCodes.BAD_REQUEST)
00189 except InvalidAppException as e:
00190 return StartAppResponse(started=False, message=str(e), error_code=StatusCodes.INTERNAL_ERROR)
00191 except NotFoundException as e:
00192 return StartAppResponse(started=False, message=str(e), error_code=StatusCodes.NOT_FOUND)
00193
00194 try:
00195 app_definitions = self._current_app_definitions
00196 app_definitions.append(app)
00197 current_apps = self._current_apps
00198 current_apps.append(App(name=appname))
00199 self._set_current_apps(current_apps, app_definitions)
00200
00201 rospy.loginfo("Launching: %s"%(app.launch))
00202 self._status_pub.publish(AppStatus(AppStatus.INFO, 'launching %s'%(app.display_name)))
00203
00204
00205 launch = roslaunch.parent.ROSLaunchParent(rospy.get_param("/run_id"),
00206 [app.launch], is_core=False,
00207 process_listeners=())
00208
00209 self._launches[appname] = launch
00210 launch._load_config()
00211
00212
00213 for N in launch.config.nodes:
00214 for t in app.interface.published_topics.keys():
00215 N.remap_args.append((t, self._app_interface + '/' + t))
00216 for t in app.interface.subscribed_topics.keys():
00217 N.remap_args.append((t, self._app_interface + '/' + t))
00218 launch.start()
00219
00220 fp = [self._app_interface + '/' + x for x in app.interface.subscribed_topics.keys()]
00221 lp = [self._app_interface + '/' + x for x in app.interface.published_topics.keys()]
00222
00223 self._interface_sync = MasterSync(self._interface_master, foreign_pub_names=fp, local_pub_names=lp)
00224
00225 thread.start_new_thread(self.app_monitor,())
00226
00227 return StartAppResponse(started=True, message="app [%s] started"%(appname), namespace=self._app_interface)
00228
00229 except Exception as e:
00230 try:
00231
00232
00233 try:
00234 if (self._launches.has_key(appname)):
00235 launch = self._launches[appname]
00236 launch.shutdown()
00237 finally:
00238 del self._launches[appname]
00239 try:
00240 self._interface_sync.stop()
00241 finally:
00242 self._interface_sync = None
00243 except:
00244 pass
00245 self._status_pub.publish(AppStatus(AppStatus.INFO, 'app start failed'))
00246 rospy.logerr("app start failed")
00247 return StartAppResponse(started=False, message="internal error [%s]"%(str(e)), error_code=StatusCodes.INTERNAL_ERROR)
00248
00249 def handle_stop_app(self, req):
00250 rospy.loginfo("handle stop app: %s"%(req.name))
00251 return self.stop_app(req.name)
00252
00253 def app_monitor(self):
00254 while self._launch:
00255 time.sleep(0.1)
00256 launch = self._launch
00257 if launch:
00258 pm = launch.pm
00259 if pm:
00260 if pm.done:
00261 time.sleep(1.0)
00262 self.stop_apps()
00263 break
00264
00265 def stop_app(self, appname):
00266 resp = StopAppResponse(stopped=False)
00267 current_app_definitions = self._current_app_definitions
00268 current_apps = self._current_apps
00269 launches = self._launches
00270 try:
00271 for app in current_app_definitions:
00272 if app.name == appname:
00273 launches[appname].shutdown()
00274 app_to_stop = current_apps[current_app_definitions.index(app)]
00275 current_apps.remove(app_to_stop)
00276 current_app_definitions.remove(app)
00277 self._set_current_apps(current_apps, current_app_definitions)
00278 resp.stopped =True
00279 except Exception as e:
00280 rospy.logerr("handle stop app: internal error %s"%(e))
00281 resp.error_code = StatusCodes.INTERNAL_ERROR
00282 resp.message = "internal error: %s"%(str(e))
00283
00284 return resp
00285
00286 def stop_apps(self):
00287 resp = StopAppResponse(stopped=False)
00288 current_app_definitions = self._current_app_definitions
00289 current_apps = self._current_apps
00290 launches = self._launches
00291 try:
00292 for app in current_app_definitions:
00293 launches[app.name].shutdown()
00294 app_to_stop = current_apps[current_app_definitions.index(app)]
00295 current_apps.remove(app_to_stop)
00296 current_app_definitions.remove(app)
00297 self._set_current_apps(current_apps, current_app_definitions)
00298 resp.stopped =True
00299 except Exception as e:
00300 rospy.logerr("handle stop app: internal error %s"%(e))
00301 resp.error_code = StatusCodes.INTERNAL_ERROR
00302 resp.message = "internal error: %s"%(str(e))
00303
00304 return resp