00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 import rospy
00011 import os
00012 import sys
00013 import traceback
00014 import roslaunch.pmon
00015 from .app import App
00016 from .app_list import AppListFile
00017 from .logger import Logger
00018 from std_msgs.msg import String
00019 from .utils import platform_compatible, platform_tuple
00020 import appmanager_msgs.msg as appmanager_msgs
00021 import appmanager_msgs.srv as appmanager_srvs
00022 import concert_msgs.msg as concert_msgs
00023 import concert_msgs.srv as concert_srvs
00024 import gateway_msgs.msg as gateway_msgs
00025 import gateway_msgs.srv as gateway_srvs
00026
00027
00028
00029
00030
00031
00032 """
00033 AppManager - Jihoon Lee(jihoonl@yujinrobot.com)
00034
00035 Feature:
00036 Configuration
00037 - app_list_directory by yaml(Done)
00038
00039 App Management
00040 - Load installed apps from app_list directory.
00041 - launches app
00042
00043 Todo:
00044 Configuration
00045 - app_store url by yaml
00046
00047 Concert Master Relation(in concert_client.py)
00048 - When a new concert master comes in network, it flips out publisher that informs platform-info, and service to listen an invitation.
00049 - When it receives a invitation from concert master, it validates the inviter with it's white/black list, then closes channels to other concert masters.
00050 - Have install/uninstall/start/stop an app services
00051
00052 App Management
00053 - have publisher that send out installed app list, available app list, and some more info. maybe latched=true one.
00054 - 'apt-get' app from app store
00055 - cache-ing the app lists
00056
00057 """
00058
00059
00060 class AppManager(object):
00061
00062 DEFAULT_APP_LIST_DIRECTORY = None
00063
00064 init_srv_name = '~init'
00065 flip_request_srv_name = '~apiflip_request'
00066 invitation_srv_name = '~invitation'
00067
00068 listapp_srv_name = 'list_apps'
00069 platform_info_srv_name = 'platform_info'
00070 start_app_srv_name = 'start_app'
00071 stop_app_srv_name = 'stop_app'
00072 log_pub_name = 'log'
00073
00074 services = {}
00075 pubs = {}
00076 gateway_srvs = {}
00077
00078 APP_STOPPED = "stopped"
00079 APP_RUNNING = "running"
00080 APP_BROKEN = "broken"
00081
00082
00083
00084
00085
00086 def __init__(self):
00087 self.param = {}
00088 self.apps = {}
00089 self.app_list = None
00090
00091 self._setup_ros_parameters()
00092 self._app_status = self.APP_STOPPED
00093
00094 roslaunch.pmon._init_signal_handlers()
00095
00096 self._set_gateway_services()
00097 self._set_platform_info()
00098
00099 self._get_installed_app_list()
00100 self._set_app_manager_api()
00101
00102 def _set_app_manager_api(self):
00103 self.services = {}
00104 self.services['init'] = rospy.Service(self.init_srv_name, appmanager_srvs.Init, self._process_init)
00105 self.services['apiflip_request'] = rospy.Service(self. flip_request_srv_name, appmanager_srvs.FlipRequest, self._process_flip_request)
00106 self.services['invitation'] = rospy.Service(self.invitation_srv_name, concert_srvs.Invitation, self._process_invitation)
00107
00108 def _set_gateway_services(self):
00109 self.gateway_srv = {}
00110 self.gateway_srv['flip'] = rospy.ServiceProxy('~flip', gateway_srvs.Remote)
00111 self.gateway_srv['advertise'] = rospy.ServiceProxy('~advertise', gateway_srvs.Advertise)
00112 self.gateway_srv['pull'] = rospy.ServiceProxy('~pull', gateway_srvs.Remote)
00113
00114 def _set_platform_info(self):
00115 self.platform_info = concert_msgs.PlatformInfo()
00116 self.platform_info.platform = concert_msgs.Constants.PLATFORM_LINUX
00117 self.platform_info.system = concert_msgs.Constants.SYSTEM_ROS
00118 self.platform_info.robot = self.param['robot_type']
00119 self.platform_info.name = self.param['robot_name']
00120
00121
00122
00123
00124
00125 def _process_init(self, req):
00126 self.name = req.name
00127 try:
00128 self.setAPIs(self.name)
00129 except Exception as unused_e:
00130 traceback.print_exc(file=sys.stdout)
00131 return appmanager_srvs.InitResponse(False)
00132 return appmanager_srvs.InitResponse(True)
00133
00134 def _process_flip_request(self, req):
00135 try:
00136 remotename = req.remotename
00137 self.remotename = remotename
00138 service = self.service_names[0:2]
00139 self.flips(remotename, service, gateway_msgs.ConnectionType.SERVICE, req.ok_flag)
00140 except Exception as unused_e:
00141 traceback.print_exc(file=sys.stdout)
00142 return appmanager_srvs.FlipRequestResponse(False)
00143
00144 return appmanager_srvs.FlipRequestResponse(True)
00145
00146 def _process_invitation(self, req):
00147 self.log(str(req))
00148
00149 service = self.service_names[2:]
00150 self.log("accepted invitation to remote concert [%s]" % str(self.remotename))
00151
00152 try:
00153 self.flips(self.remotename, service, gateway_msgs.ConnectionType.SERVICE, req.ok_flag)
00154 self.flips(self.remotename, self.pub_names, gateway_msgs.ConnectionType.PUBLISHER, req.ok_flag)
00155 except Exception as unused_e:
00156 traceback.print_exc(file=sys.stdout)
00157 return concert_srvs.InvitationResponse(False)
00158 return concert_srvs.InvitationResponse(True)
00159
00160 def _process_platform_info(self, req):
00161 return concert_srvs.GetPlatformInfoResponse(self.platform_info)
00162
00163 def _process_get_app_list(self, req):
00164 apps_description = appmanager_srvs.GetAppListResponse()
00165
00166 for app_name in self.apps['from_source']:
00167 app = self.apps['from_source'][app_name]
00168 a = appmanager_msgs.AppDescription()
00169 a.name = app.data['name']
00170 a.display = app.data['display']
00171 a.description = app.data['description']
00172 a.platform = app.data['platform']
00173 a.status = app.data['status']
00174 apps_description.apps.append(a)
00175
00176 return apps_description
00177
00178 def _process_start_app(self, req):
00179 resp = appmanager_srvs.StartAppResponse()
00180 if self._app_status == self.APP_RUNNING:
00181 resp.started = False
00182 resp.message = "an app is already running"
00183 return resp
00184
00185 rospy.loginfo("App Manager : starting app : " + req.name)
00186
00187 resp.started, resp.message, subscribers, publishers, services = \
00188 self.apps['from_source'][req.name].start(self.param['robot_name'], req.remappings)
00189
00190
00191 print subscribers
00192 print publishers
00193
00194 self.log(self.remotename)
00195 if self.remotename:
00196 self.flips(self.remotename, subscribers, gateway_msgs.ConnectionType.SUBSCRIBER, True)
00197 self.flips(self.remotename, publishers, gateway_msgs.ConnectionType.PUBLISHER, True)
00198 self.flips(self.remotename, services, gateway_msgs.ConnectionType.SERVICE, True)
00199 if resp.started:
00200 self._app_status = self.APP_RUNNING
00201 return resp
00202
00203 def _process_stop_app(self, req):
00204 if self._app_status == self.APP_STOPPED:
00205 return
00206 rospy.loginfo("App Manager : stopping app : " + req.name)
00207 resp = appmanager_srvs.StopAppResponse()
00208
00209 resp.stopped, resp.message, subscribers, publishers, services = self.apps['from_source'][req.name].stop()
00210
00211 if self.remotename:
00212 self.flips(self.remotename, subscribers, gateway_msgs.ConnectionType.SUBSCRIBER, False)
00213 self.flips(self.remotename, publishers, gateway_msgs.ConnectionType.PUBLISHER, False)
00214 self.flips(self.remotename, services, gateway_msgs.ConnectionType.SERVICE, False)
00215 if resp.stopped:
00216 self._app_status = self.APP_STOPPED
00217 return resp
00218
00219
00220
00221
00222
00223 def createRemoteRule(self, gateway, rule):
00224 r = gateway_msgs.RemoteRule()
00225 r.gateway = gateway
00226 r.rule = rule
00227
00228 return r
00229
00230 def createRule(self, name, api_type):
00231 r = gateway_msgs.Rule()
00232 r.name = name
00233 r.type = api_type
00234 r.node = ''
00235 return r
00236
00237 def _setup_ros_parameters(self):
00238 rospy.logdebug("App Manager : parsing parameters")
00239 param = {}
00240 param['robot_type'] = rospy.get_param('~robot_type')
00241 param['robot_name'] = rospy.get_param('~robot_name')
00242 param['app_store_url'] = rospy.get_param('~app_store_url', '')
00243 param['platform_info'] = rospy.get_param('~platform_info', '')
00244 param['white_list'] = rospy.get_param('~whitelist', '')
00245 param['black_list'] = rospy.get_param('~black_list', '')
00246 param['is_alone'] = rospy.get_param('~is_alone', False)
00247 param['app_lists'] = rospy.get_param('~app_lists', '').split(';')
00248
00249
00250 self.param = param
00251
00252 def _get_installed_app_list(self):
00253 '''
00254 Sets up an app directory and load installed app from given directory
00255 '''
00256 apps = {}
00257 apps['from_source'] = {}
00258
00259 for filename in self.param['app_lists']:
00260
00261 app_list_file = AppListFile(filename)
00262
00263 for app in app_list_file.available_apps:
00264 if platform_compatible(platform_tuple(self.platform_info.platform, self.platform_info.system, self.platform_info.robot), app.data['platform']):
00265 apps['from_source'][app.data['name']] = app
00266 self.apps = apps
00267
00268 def _load(self, directory, typ):
00269 '''
00270 It searchs *.app in directories
00271 '''
00272 applist = []
00273 for dpath, unused_, files in os.walk(directory):
00274 apps = [f for f in files if f.endswith(typ)]
00275 apps_with_path = [dpath + '/' + a for a in apps]
00276 apps_name = [a[0:len(a) - len(typ)] for a in apps]
00277
00278 applist += list(zip(apps_name, apps_with_path))
00279
00280 return applist
00281
00282 def setAPIs(self, namespace):
00283 rospy.loginfo("App Manager : advertising services")
00284 self.platform_info.name = namespace
00285 service_names = [namespace + '/' + self.listapp_srv_name, '/' + namespace + '/' + self.platform_info_srv_name, '/' + namespace + '/' + self.start_app_srv_name, '/' + namespace + '/' + self.stop_app_srv_name]
00286 self.service_names = service_names
00287 self.services['list_apps'] = rospy.Service(service_names[0], appmanager_srvs.GetAppList, self._process_get_app_list)
00288 self.services['platform_info'] = rospy.Service(service_names[1], concert_srvs.GetPlatformInfo, self._process_platform_info)
00289 self.services['start_app'] = rospy.Service(service_names[2], appmanager_srvs.StartApp, self._process_start_app)
00290 self.services['stop_app'] = rospy.Service(service_names[3], appmanager_srvs.StopApp, self._process_stop_app)
00291
00292 self.pubs = {}
00293 pub_names = ['/' + namespace + '/' + self.log_pub_name]
00294 self.pub_names = pub_names
00295 self.pubs['log'] = rospy.Publisher(self.pub_names[0], String)
00296
00297
00298 self.logger = Logger(sys.stdout)
00299 sys.stdout = self.logger
00300 self.logger.addCallback(self.process_stdmsg)
00301
00302 def flips(self, remotename, topics, type, ok_flag):
00303 if len(topics) == 0:
00304 return
00305 req = gateway_srvs.RemoteRequest()
00306 req.cancel = not ok_flag
00307
00308 req.remotes = []
00309
00310 for t in topics:
00311 req.remotes.append(self.createRemoteRule(remotename, self.createRule(t, type)))
00312
00313 resp = self.gateway_srv['flip'](req)
00314
00315 if resp.result == 0:
00316 rospy.loginfo("App Manager : successfully flipped %s" % str(topics))
00317 else:
00318 rospy.logerr("App Manager : failed to flip [%s]" % resp.error_message)
00319
00320 def process_stdmsg(self, message):
00321 self.pubs['log'].publish(message)
00322
00323 def log(self, msg):
00324 rospy.loginfo("App Manager : " + msg)
00325
00326 def logerr(self, msg):
00327 rospy.logerr("App Manager : " + msg)
00328
00329 def spin(self):
00330
00331
00332 rospy.spin()
00333