Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 import os
00011
00012 import rospy
00013 import rocon_python_comms
00014
00015 from rocon_std_msgs.msg import Remapping, KeyValue
00016 from rocon_app_manager_msgs.msg import Status, RappList
00017 from rocon_app_manager_msgs.srv import StartRapp, StopRapp
00018
00019
00020
00021
00022
00023 def list_rapp_msg_to_dict(list_rapp):
00024 """
00025 convert msg to dict
00026 """
00027 dict_rapp = {}
00028 for rapp in list_rapp:
00029 name = rapp.name
00030 dict_rapp[name] = {}
00031 dict_rapp[name]["status"] = rapp.status
00032 dict_rapp[name]["name"] = rapp.name
00033 dict_rapp[name]["display_name"] = rapp.display_name
00034 dict_rapp[name]["description"] = rapp.description
00035 dict_rapp[name]["compatibility"] = rapp.compatibility
00036 dict_rapp[name]["preferred"] = rapp.preferred
00037 dict_rapp[name]["icon"] = rapp.icon
00038 dict_rapp[name]["implementations"] = rapp.implementations
00039 dict_rapp[name]["public_interface"] = rapp.public_interface
00040 dict_rapp[name]["public_parameters"] = rapp.public_parameters
00041 return dict_rapp
00042
00043
00044 RAPP_LIST_TOPIC = 'rapp_list'
00045
00046 class QtRappManagerInfo(object):
00047
00048
00049 def __init__(self, update_rapp_callback):
00050 self._available_rapps = {}
00051 self._running_rapps = {}
00052 self._update_rapps_callback = update_rapp_callback
00053
00054 self._current_namespace = ''
00055 self._current_subscriber = None
00056
00057 def _update_rapps(self, data):
00058 """
00059 Update the available rapp list
00060
00061 @param data: information of rapps
00062 @type rocon_app_manager_msgs/RappList
00063 """
00064 self._available_rapps = list_rapp_msg_to_dict(data.available_rapps)
00065 self._running_rapps = list_rapp_msg_to_dict(data.running_rapps)
00066
00067
00068 def _process_rapp_list_msg(self, msg):
00069 """
00070 Update the available rapp list
00071
00072 @param data: information of rapps
00073 @type rocon_app_manager_msgs/RappList
00074 """
00075
00076 self._available_rapps = list_rapp_msg_to_dict(msg.available_rapps)
00077 self._running_rapps = list_rapp_msg_to_dict(msg.running_rapps)
00078 self._update_rapps_callback()
00079
00080 def select_rapp_manager(self, namespace):
00081 if self._current_subscriber and self._current_namespace != namespace:
00082 self._current_subscriber.unregister()
00083 self._current_subscriber = None
00084 self._current_subscriber = rospy.Subscriber(namespace + RAPP_LIST_TOPIC, RappList, self._process_rapp_list_msg)
00085 self._current_namespace = namespace
00086
00087 def get_available_rapps(self):
00088 return self._available_rapps
00089
00090 def _get_namespaces(self):
00091 """
00092 Getting the name space with running the rapp
00093 @return name space list
00094 @type list
00095 """
00096 get_rapp_list_service_names = rocon_python_comms.find_service('rocon_app_manager_msgs/GetRappList', timeout=rospy.rostime.Duration(5.0), unique=False)
00097 return get_rapp_list_service_names
00098
00099 def _get_rapps(self, namespace):
00100 """
00101 Getting the rapp list using service calling
00102 @param namespace: namespace of running rapp
00103 @type String
00104
00105 @param service_name: service_name
00106 @type String
00107 """
00108 service_handle = rospy.ServiceProxy(namespace + 'list_rapps', GetRappList)
00109 self._update_rapps(service_handle())
00110
00111 def start_rapp(self, rapp_name, remappings, parameters):
00112 """
00113 Start rapp
00114
00115 :param rapp_name: rapp to start
00116 :type rapp_name: str
00117 :param remappings: remapping rules
00118 :type remappings: list
00119 :param parameters: public parameters
00120 :type parameters: list
00121 """
00122
00123 remaps = [Remapping(key, value) for key, value in remappings]
00124 params = [KeyValue(k,v) for k, v in parameters]
00125
00126 print('Starting %s with %s, %s'%(rapp_name, str(params), str(remaps)))
00127 service_handle = rospy.ServiceProxy(self._current_namespace + 'start_rapp', StartRapp)
00128 call_result = service_handle(rapp_name, remaps, params)
00129
00130 if call_result.started:
00131 self._current_rapp = rapp_name
00132
00133 return call_result
00134
00135 def stop_rapp(self):
00136 """
00137 Stop rapp
00138
00139 @param namespace: name space of running rapp
00140 @type String
00141 """
00142 service_handle = rospy.ServiceProxy(self._current_namespace + 'stop_rapp', StopRapp)
00143 call_result = service_handle()
00144 return call_result
00145
00146 def get_running_rapps(self):
00147 return self._running_rapps
00148
00149 def is_running_rapp(self, rapp):
00150 if rapp['name'] in self._running_rapps.keys():
00151 return True
00152 else:
00153 return False