interactive_client_interface.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/rocon_qt_gui/license/LICENSE
00005 #
00006 ##############################################################################
00007 # Imports
00008 ##############################################################################
00009 
00010 from functools import partial
00011 import json
00012 import os
00013 import tempfile
00014 import types
00015 import urllib
00016 from urlparse import urlparse
00017 import uuid
00018 import yaml
00019 
00020 from rocon_app_manager_msgs.msg import ErrorCodes
00021 from rocon_console import console
00022 import rocon_interactions
00023 import rocon_interaction_msgs.msg as rocon_interaction_msgs
00024 import rocon_interaction_msgs.srv as rocon_interaction_srvs
00025 import rocon_interactions.web_interactions as web_interactions
00026 import rocon_launch
00027 import rocon_python_comms
00028 import rocon_python_utils
00029 import rocon_std_msgs.msg as rocon_std_msgs
00030 import rocon_uri
00031 import rospkg
00032 from rospkg.os_detect import OsDetect
00033 import rospy
00034 
00035 from . import utils
00036 from .launch import LaunchInfo, RosLaunchInfo
00037 from .interactions import Interaction
00038 from .interactions_table import InteractionsTable
00039 
00040 ##############################################################################
00041 # Interactive Client Interface
00042 ##############################################################################
00043 
00044 
00045 class InteractiveClientInterface():
00046 
00047     shutdown_timeout = 0.5
00048 
00049     """
00050     Time to wait before shutting down so remocon status updates can be received and processed
00051     by the interactions manager (important for pairing interactions).
00052     """
00053 
00054     def __init__(self, stop_interaction_postexec_fn):
00055         '''
00056           @param stop_app_postexec_fn : callback to fire when a listener detects an app getting stopped.
00057           @type method with no args
00058         '''
00059         self._interactions_table = InteractionsTable()
00060         self._stop_interaction_postexec_fn = stop_interaction_postexec_fn
00061         self.is_connect = False
00062         self.key = uuid.uuid4()
00063         self._ros_master_port = None
00064         try:
00065             self._roslaunch_terminal = rocon_launch.create_terminal()
00066         except (rocon_launch.UnsupportedTerminal, rocon_python_comms.NotFoundException) as e:
00067             console.warning("Cannot find a suitable terminal, falling back to the current terminal [%s]" % str(e))
00068             self._roslaunch_terminal = rocon_launch.create_terminal(rocon_launch.terminals.active)
00069 
00070         # this might be naive and only work well on ubuntu...
00071         os_codename = OsDetect().get_codename()
00072         webbrowser_codename = utils.get_web_browser_codename()
00073         # this would be good as a persistant variable so the user can set something like 'Bob'
00074         self.name = "rqt_remocon_" + self.key.hex
00075         self.rocon_uri = rocon_uri.parse(
00076             "rocon:/pc/" + self.name + "/" + rocon_std_msgs.Strings.URI_WILDCARD + "/" + os_codename + "|" + webbrowser_codename
00077         )
00078         # be also great to have a configurable icon...with a default
00079         self.platform_info = rocon_std_msgs.PlatformInfo(version=rocon_std_msgs.Strings.ROCON_VERSION,
00080                                                          uri=str(self.rocon_uri),
00081                                                          icon=rocon_std_msgs.Icon()
00082                                                          )
00083         console.logdebug("Interactive Client : initialised")
00084         self.pairing = None  # if an interaction is currently pairing, this will store its hash
00085 
00086         # expose underlying functionality higher up
00087         self.interactions = self._interactions_table.generate_role_view
00088         """Get a dictionary of interactions belonging to the specified role."""
00089 
00090     def _connect_with_ros_init_node(self, ros_master_uri="http://localhost:11311", host_name='localhost'):
00091         # uri is obtained from the user, stored in ros_master_uri
00092         os.environ["ROS_MASTER_URI"] = ros_master_uri
00093         os.environ["ROS_HOSTNAME"] = host_name
00094         rospy.init_node(self.name, disable_signals=True)
00095         return self._connect(ros_master_uri, host_name)
00096 
00097     def _connect(self, ros_master_uri="http://localhost:11311", host_name='localhost'):
00098 
00099         self._ros_master_port = urlparse(os.environ["ROS_MASTER_URI"]).port
00100         console.logdebug("Interactive Client : Connection Details")
00101         console.logdebug("Interactive Client :   Node Name: " + self.name)
00102         console.logdebug("Interactive Client :   ROS_MASTER_URI: " + ros_master_uri)
00103         console.logdebug("Interactive Client :   ROS_HOSTNAME: " + host_name)
00104         console.logdebug("Interactive Client :   ROS_MASTER_PORT: %s" % self._ros_master_port)
00105 
00106         # Need to make sure we give init a unique node name and we need a unique uuid
00107         # for the remocon-role manager interaction anyway:
00108 
00109         try:
00110             console.logdebug("Interactive Client : Get interactions service Handle")
00111             interactions_namespace = rocon_python_comms.find_service_namespace('get_interactions', 'rocon_interaction_msgs/GetInteractions', unique=True)
00112             remocon_services = self._set_remocon_services(interactions_namespace)
00113         except rocon_python_comms.MultipleFoundException as e:
00114             message = "multiple interactions' publications and services [%s] are found. Please check services" % str(e)
00115             console.logerror("InteractiveClientInterface : %s" % message)
00116             return (False, message)
00117         except rocon_python_comms.NotFoundException as e:
00118             message = "failed to find all of the interactions' publications and services for [%s]" % str(e)
00119             console.logerror("InteractiveClientInterface : %s" % message)
00120             return (False, message)
00121 
00122         self.get_interactions_service_proxy = rospy.ServiceProxy(remocon_services['get_interactions'], rocon_interaction_srvs.GetInteractions)
00123         self.get_roles_service_proxy = rospy.ServiceProxy(remocon_services['get_roles'], rocon_interaction_srvs.GetRoles)
00124         self.request_interaction_service_proxy = rospy.ServiceProxy(remocon_services['request_interaction'], rocon_interaction_srvs.RequestInteraction)
00125         self.remocon_status_pub = rospy.Publisher("remocons/" + self.name, rocon_interaction_msgs.RemoconStatus, latch=True, queue_size=10)
00126 
00127         try:
00128             # if its available, should be quick to find this one since we found the others...
00129             pairing_topic_name = rocon_python_comms.find_topic('rocon_interaction_msgs/Pair', timeout=rospy.rostime.Duration(0.5), unique=True)
00130             self.pairing_status_subscriber = rospy.Subscriber(pairing_topic_name, rocon_interaction_msgs.Pair, self._subscribe_pairing_status_callback)
00131         except rocon_python_comms.NotFoundException as e:
00132             console.logdebug("Interactive Client : support for paired interactions disabled [not found]")
00133 
00134         self._publish_remocon_status()
00135         self.is_connect = True
00136         return (True, "success")
00137 
00138     def shutdown(self):
00139         if(self.is_connect != True):
00140             return
00141         else:
00142             console.logdebug("Interactive Client : shutting down all interactions")
00143             for interaction in self._interactions_table.interactions:
00144                 self.stop_interaction(interaction.hash)
00145 
00146             rospy.rostime.wallsleep(InteractiveClientInterface.shutdown_timeout)
00147             console.logdebug("Interactive Client : signaling shutdown.")
00148             rospy.signal_shutdown("shut down remocon_info")
00149             while not rospy.is_shutdown():
00150                 rospy.rostime.wallsleep(0.1)
00151 
00152             console.logdebug("Interactive Client : has shutdown.")
00153 
00154     def get_role_list(self):
00155         if not self.is_connect:
00156             rospy.logwarn("InteractiveClientInterface : aborting a request to 'get_roles' as we are not connected to a rocon interactions manager.")
00157             return []
00158         try:
00159             response = self.get_roles_service_proxy(self.platform_info.uri)
00160         except (rospy.ROSInterruptException, rospy.ServiceException):
00161             return []
00162         return response.roles
00163 
00164     def select_role(self, role_name):
00165         """
00166         Contact the interactions manager and retrieve all the interactions
00167         associated to a particular role.
00168 
00169         :param str role_name: role to request list of interactions for.
00170         """
00171         call_result = self.get_interactions_service_proxy([role_name], self.platform_info.uri)
00172         for msg in call_result.interactions:
00173             self._interactions_table.append(Interaction(msg))
00174         # could use a whole bunch of exception checking here, removing
00175         # self.interactions[role_name] if necessary.
00176 
00177     def has_running_interactions(self):
00178         """
00179         Identify if this client has any running interactions. Used by the gui above
00180         to enable/disable a button that will trigger stoppage of all running interactions.
00181         """
00182         for interaction in self._interactions_table.interactions:
00183             if interaction.launch_list.keys():
00184                 return True
00185         return False
00186 
00187     def start_interaction(self, role_name, interaction_hash):
00188         """
00189         :param str interaction_hash: the key
00190         :param str role_name: help refine the search by specifying what role this interaction is for
00191 
00192         :returns: result of the effort to start an interaction, with a message if there was an error.
00193         :rtype: (bool, message)
00194         """
00195         interaction = self._interactions_table.find(interaction_hash)
00196         if interaction is None:
00197             return (False, "interaction key %s not found in interactions table" % interaction_hash)
00198         if interaction.role != role_name:
00199             return (False, "interaction key %s is in the interactions table, but under another role" % interaction_hash)
00200         if self.pairing and interaction.is_paired_type():
00201             return (False, "remocon already pairing (%s,%s) and additional pairing is not permitted " % (interaction.pairing.rapp, interaction.display_name))
00202 
00203         # get the permission
00204         call_result = self.request_interaction_service_proxy(remocon=self.name, hash=interaction.hash)
00205 
00206         if call_result.error_code == ErrorCodes.SUCCESS:
00207             console.logdebug("Interactive Client : interaction request granted")
00208             try:
00209                 (app_executable, start_app_handler) = self._determine_interaction_type(interaction)
00210             except rocon_interactions.InvalidInteraction as e:
00211                 return False, ("invalid interaction specified [%s]" % str(e))
00212             result = start_app_handler(interaction, app_executable)
00213             if result:
00214                 self._publish_remocon_status()
00215                 if interaction.is_paired_type():
00216                     self.pairing = interaction.hash
00217                 return (result, "success")
00218             else:
00219                 return (result, "unknown")
00220         else:
00221             return False, ("interaction request rejected [%s]" % call_result.message)
00222         return (True, "success")
00223 
00224     def _determine_interaction_type(self, interaction):
00225         '''
00226           Classifies the interaction based on the name string and some intelligent
00227           (well, reasonably) parsing of that string.
00228            - paired dummy (by empty name)
00229            - ros launcher (by .launch extension)
00230            - ros runnable (by roslib find_resource success)
00231            - web app      (by web_interactions.parse)
00232            - web url      (by web_interactions.parse)
00233            - global executable (fallback option)
00234         '''
00235         # pairing trigger (i.e. dummy interaction)
00236         if not interaction.name:
00237             console.logdebug("Interactive Client : start a dummy interaction for triggering a pair")
00238             return ('', self._start_dummy_interaction)
00239         # roslaunch
00240         try:
00241             launcher_filename = rocon_python_utils.ros.find_resource_from_string(interaction.name, extension='launch')
00242             if interaction.remappings:
00243                 raise rocon_interactions.InvalidInteraction("remappings are not yet enabled for roslaunchable interactions (workaround: try remapping via interaction parameters and roslaunch args)[%s]" % interaction.name)
00244             console.logdebug("Interactive Client : roslaunchable [%s]" % interaction.name)
00245             return (launcher_filename, self._start_roslaunch_interaction)
00246         except (rospkg.ResourceNotFound, ValueError):
00247             unused_filename, extension = os.path.splitext(interaction.name)
00248             if extension == '.launch':
00249                 raise rocon_interactions.InvalidInteraction("could not find %s on the filesystem" % interaction.name)
00250             else:
00251                 pass
00252         # rosrun
00253         try:
00254             rosrunnable_filename = rocon_python_utils.ros.find_resource_from_string(interaction.name)
00255             console.logdebug("Interactive Client : start_app_rosrunnable [%s]" % interaction.name)
00256             return (rosrunnable_filename, self._start_rosrunnable_interaction)
00257         except rospkg.ResourceNotFound:
00258             pass
00259         except Exception:
00260             pass
00261         # web url/app
00262         web_interaction = web_interactions.parse(interaction.name)
00263         if web_interaction is not None:
00264             if web_interaction.is_web_url():
00265                 console.logdebug("Interactive Client : _start_weburl_interaction [%s]" % web_interaction.url)
00266                 return (web_interaction.url, self._start_weburl_interaction)
00267             elif web_interaction.is_web_app():
00268                 console.logdebug("Interactive Client : _start_webapp_interaction [%s]" % web_interaction.url)
00269                 return (web_interaction.url, self._start_webapp_interaction)
00270         # executable
00271         if rocon_python_utils.system.which(interaction.name) is not None:
00272             console.logdebug("Interactive Client : _start_global_executable_interaction [%s]")
00273             return (interaction.name, self._start_global_executable_interaction)
00274         else:
00275             raise rocon_interactions.InvalidInteraction("could not find a valid rosrunnable or global executable for '%s' (mispelt, not installed?)" % interaction.name)
00276 
00277     def _start_dummy_interaction(self, interaction, unused_filename):
00278         console.loginfo("InteractiveClientInterface : starting paired dummy interaction")
00279         anonymous_name = interaction.name + "_" + uuid.uuid4().hex
00280         #process_listener = partial(self._process_listeners, anonymous_name, 1)
00281         #process = rocon_python_utils.system.Popen([rosrunnable_filename], postexec_fn=process_listener)
00282         interaction.launch_list[anonymous_name] = LaunchInfo(anonymous_name, True, None)  # empty shutdown function
00283         return True
00284 
00285     def _start_roslaunch_interaction(self, interaction, roslaunch_filename):
00286         '''
00287           Start a ros launchable application, applying parameters and remappings if specified.
00288         '''
00289         anonymous_name = interaction.display_name.lower().replace(" ", "_") + "_" + uuid.uuid4().hex
00290         launch_configuration = rocon_launch.RosLaunchConfiguration(
00291             name=roslaunch_filename,
00292             package=None,
00293             port=self._ros_master_port,
00294             title=interaction.display_name,
00295             namespace=interaction.namespace,
00296             args=self._prepare_roslaunch_args(interaction.parameters),
00297             options="--screen"
00298         )
00299         process_listener = partial(self._process_listeners, anonymous_name, 1)
00300         (process, meta_roslauncher) = self._roslaunch_terminal.spawn_roslaunch_window(launch_configuration, postexec_fn=process_listener)
00301         interaction.launch_list[anonymous_name] = RosLaunchInfo(anonymous_name, True, process, self._roslaunch_terminal.shutdown_roslaunch_windows, [meta_roslauncher])
00302         return True
00303 
00304     def _start_rosrunnable_interaction(self, interaction, rosrunnable_filename):
00305         '''
00306           Launch a rosrunnable application. This does not apply any parameters
00307           or remappings (yet).
00308         '''
00309         # the following is guaranteed since we came back from find_resource calls earlier
00310         # note we're overriding the rosrunnable filename here - rosrun doesn't actually take the full path.
00311         package_name, rosrunnable_filename = interaction.name.split('/')
00312         name = os.path.basename(rosrunnable_filename).replace('.', '_')
00313         anonymous_name = name + "_" + uuid.uuid4().hex
00314         process_listener = partial(self._process_listeners, anonymous_name, 1)
00315         cmd = ['rosrun', package_name, rosrunnable_filename, '__name:=%s' % anonymous_name]
00316         remapping_args = []
00317         for remap in interaction.remappings:
00318             remapping_args.append(remap.remap_from + ":=" + remap.remap_to)
00319         cmd.extend(remapping_args)
00320         cmd.extend(self._prepare_command_line_parameters(interaction.parameters))
00321         console.logdebug("Interactive Client : rosrunnable command %s" % cmd)
00322         process = rocon_python_utils.system.Popen(cmd, postexec_fn=process_listener)
00323         interaction.launch_list[anonymous_name] = LaunchInfo(anonymous_name, True, process)
00324         return True
00325 
00326     def _start_global_executable_interaction(self, interaction, filename):
00327         console.logwarn("Interactive Client : starting global executable [%s]" % interaction.name)
00328         name = os.path.basename(filename).replace('.', '_')
00329         anonymous_name = name + "_" + uuid.uuid4().hex
00330         process_listener = partial(self._process_listeners, anonymous_name, 1)
00331         cmd = [filename]
00332         remapping_args = []
00333         for remap in interaction.remappings:
00334             remapping_args.append(remap.remap_from + ":=" + remap.remap_to)
00335         cmd.extend(remapping_args)
00336         cmd.extend(self._prepare_command_line_parameters(interaction.parameters))
00337         console.logdebug("Interactive Client : global executable command %s" % cmd)
00338         process = rocon_python_utils.system.Popen(cmd, postexec_fn=process_listener)
00339         interaction.launch_list[anonymous_name] = LaunchInfo(anonymous_name, True, process)
00340         return True
00341 
00342     def _start_weburl_interaction(self, interaction, url):
00343         """
00344         We only need the url here and then do a system check for a web browser.
00345         """
00346         web_browser = utils.get_web_browser()
00347         if web_browser is not None:
00348             name = os.path.basename(web_browser).replace('.', '_')
00349             anonymous_name = name + "_" + uuid.uuid4().hex
00350             process_listener = partial(self._process_listeners, anonymous_name, 1)
00351             process = rocon_python_utils.system.Popen([web_browser, "--new-window", url], postexec_fn=process_listener)
00352             interaction.launch_list[anonymous_name] = LaunchInfo(anonymous_name, True, process)
00353             return True
00354         else:
00355             return False
00356 
00357     def _start_webapp_interaction(self, interaction, base_url):
00358         """
00359         Need to work out the extended url (with args, parameters and remappings) here and then feed that to a
00360         detected browser.
00361 
00362         :param base_url str: the web app url without all of the attached variables.
00363         """
00364         web_browser = utils.get_web_browser()
00365         if web_browser is not None:
00366             url = self._prepare_webapp_url(interaction, base_url)
00367             name = os.path.basename(web_browser).replace('.', '_')
00368             anonymous_name = name + "_" + uuid.uuid4().hex
00369             process_listener = partial(self._process_listeners, anonymous_name, 1)
00370             process = rocon_python_utils.system.Popen([web_browser, "--new-window", url], postexec_fn=process_listener)
00371             interaction.launch_list[anonymous_name] = LaunchInfo(anonymous_name, True, process)
00372             return True
00373         else:
00374             return False
00375 
00376     def stop_all_interactions(self):
00377         """
00378         This is the big showstopper - stop them all!
00379         """
00380         running_interactions = []
00381         for interaction in self._interactions_table.interactions:
00382             for unused_process_name in interaction.launch_list.keys():
00383                 running_interactions.append(interaction.hash)
00384         for interaction_hash in running_interactions:
00385             self.stop_interaction(interaction_hash)
00386 
00387     def stop_interaction(self, interaction_hash):
00388         """
00389         This stops all launches for an interaction of a particular type.
00390         """
00391         interaction = self._interactions_table.find(interaction_hash)
00392         if interaction is None:
00393             console.logwarn("Interactive Client : interaction key %s not found in interactions table" % interaction_hash)
00394             return (False, "interaction key %s not found in interactions table" % interaction_hash)
00395         try:
00396             for launch_info in interaction.launch_list.values():
00397                 if launch_info.running:
00398                     launch_info.shutdown()
00399                     console.loginfo("Interactive Client : interaction stopped [%s]" % (launch_info.name))
00400                     del interaction.launch_list[launch_info.name]
00401                 elif launch_info.process == None:
00402                     launch_info.running = False
00403                     console.loginfo("Interactive Client : no attached interaction process to stop [%s]" % (launch_info.name))
00404                     del interaction.launch_list.launch_list[launch_info.name]
00405                 else:
00406                     console.loginfo("Interactive Client : interaction is already stopped [%s]" % (launch_info.name))
00407                     del interaction.launch_list.launch_list[launch_info.name]
00408         except Exception as e:
00409             console.logerror("Interactive Client : error trying to stop an interaction [%s][%s]" % (type(e), str(e)))
00410             # this is bad...should not create bottomless exception buckets.
00411             return (False, "unknown failure - (%s)(%s)" % (type(e), str(e)))
00412         #console.logdebug("Interactive Client : interaction's updated launch list- %s" % str(interaction.launch_list))
00413         if interaction.is_paired_type():
00414             self.pairing = None
00415         self._publish_remocon_status()
00416         return (True, "success")
00417 
00418     def _process_listeners(self, name, exit_code):
00419         '''
00420           Callback function used to catch terminating applications and cleanup appropriately.
00421 
00422           @param name : name of the launched process stored in the interactions index.
00423           @type str
00424 
00425           @param exit_code : could be utilised from roslaunched processes but not currently used.
00426           @type int
00427         '''
00428         console.logdebug("Interactive Client : process_listener detected terminating interaction [%s]" % name)
00429         for interaction in self._interactions_table.interactions:
00430             if name in interaction.launch_list:
00431                 del interaction.launch_list[name]
00432                 # toggle the pairing indicator if it was a pairing interaction
00433                 if interaction.is_paired_type():
00434                     self.pairing = None
00435                 if not interaction.launch_list:
00436                     # inform the gui to update
00437                     self._stop_interaction_postexec_fn()
00438                 # update the rocon interactions handler
00439                 self._publish_remocon_status()
00440             else:
00441                 console.logwarn("Interactive Client : process_listener detected unknown terminating interaction [%s]" % name)
00442 
00443     ######################################
00444     # Ros Comms
00445     ######################################
00446 
00447     def _publish_remocon_status(self):
00448         remocon_status = rocon_interaction_msgs.RemoconStatus()
00449         remocon_status.platform_info = self.platform_info
00450         remocon_status.uuid = str(self.key.hex)
00451         remocon_status.version = rocon_std_msgs.Strings.ROCON_VERSION
00452         running_interactions = []
00453         for interaction in self._interactions_table.interactions:
00454             for unused_process_name in interaction.launch_list.keys():
00455                 running_interactions.append(interaction.hash)
00456         remocon_status.running_interactions = running_interactions
00457         console.logdebug("Interactive Client : publishing remocon status")
00458         self.remocon_status_pub.publish(remocon_status)
00459 
00460     def _subscribe_pairing_status_callback(self, msg):
00461         console.logdebug("Interactive Client : pairing status callback [%s][%s]" % (msg.rapp, msg.remocon))
00462         if self.pairing:
00463             if not msg.rapp and msg.remocon == self.name:
00464                 console.logdebug("Interactive Client : the rapp in this paired interaction terminated")
00465                 # there will only ever be one allowed instance of a paired interaction, so ok to call a stop to all instances of this interaction type
00466                 self.stop_interaction(self.pairing)
00467                 # updat the gui
00468                 self._stop_interaction_postexec_fn()
00469 
00470     ######################################
00471     # Utilities
00472     ######################################
00473 
00474     def _set_remocon_services(self, interactions_namespace):
00475         """
00476             setting up remocon-interaction manager apis. and check if the services are available
00477 
00478             :param str interactions_namespace : namespace to contact interaction manager
00479 
00480             :returns: remocon service apis
00481             :rtype: dict
00482         """
00483         remocon_services = {}
00484         remocon_services['get_interactions'] = interactions_namespace + '/' + 'get_interactions'
00485         remocon_services['get_roles'] = interactions_namespace + '/' + 'get_roles'
00486         remocon_services['request_interaction'] = interactions_namespace + '/' + 'request_interaction'
00487 
00488         for service_name in remocon_services.keys():
00489             if not rocon_python_comms.service_is_available(remocon_services[service_name]):
00490                 raise rocon_python_comms.NotFoundException("'%s' service is not validated" % service_name)
00491 
00492         return remocon_services
00493 
00494     def _prepare_webapp_url(self, interaction, base_url):
00495         """
00496            url synthesiser for sending remappings and parameters information.
00497            We convert the interaction parameter (yaml string) and remapping (rocon_std_msgs.Remapping[])
00498            variables into generic python list/dictionary objects and convert these into
00499            json strings as it makes it easier for web apps to handle them.
00500         """
00501         interaction_data = {}
00502         interaction_data['display_name'] = interaction.display_name
00503         # parameters
00504         interaction_data['parameters'] = yaml.load(interaction.parameters)
00505         # remappings
00506         interaction_data['remappings'] = {}  # need to create a dictionary for easy parsing (note: interaction.remappings is a list of rocon_std_msgs.Remapping)
00507         for r in interaction.remappings:
00508             interaction_data['remappings'][r.remap_from] = r.remap_to
00509         # package all the data in json format and dump it to one query string variable
00510         console.logdebug("Remocon Info : web app query string %s" % interaction_data)
00511         query_string_mappings = {}
00512         query_string_mappings['interaction_data'] = json.dumps(interaction_data)
00513         # constructing the url
00514         return base_url + "?" + urllib.urlencode(query_string_mappings)
00515 
00516     def _prepare_command_line_parameters(self, interaction_parameters):
00517         """
00518         Convert the interaction specified yaml string into command line parameters that can
00519         be passed to rosrunnable or global nodes.
00520 
00521         :param str interaction_parameters: parameters specified as a yaml string
00522 
00523         :returns: the parameters as command line args
00524         :rtype: str[]
00525         """
00526         parameters = []
00527         parameter_dictionary = yaml.load(interaction_parameters)  # convert from yaml string into python dictionary
00528         if parameter_dictionary is not None:  # None when there is no yaml configuration
00529             for name, value in parameter_dictionary.items():
00530                 if type(value) is types.DictType or type(value) is types.ListType:
00531                     parameters.append('_' + name + ':=' + yaml.dump(value))
00532                 else:  # it's a dict or list, so dump it
00533                     parameters.append('_' + name + ':=' + str(value))
00534         return parameters
00535 
00536     def _prepare_roslaunch_args(self, interaction_parameters):
00537         """
00538         Convert the interaction specified yaml string into roslaunch args
00539         to be passed to the roslaunchable. Note that we only use a constrained
00540         subset of yaml to be compatible with roslaunch args here.
00541         The root type has to be a dict and values themselves
00542         may not be dicts or lists.
00543 
00544         :param str interaction_parameters: parameters specified as a yaml string
00545 
00546         :returns: the parameters as roslaunch args key-value pairs
00547         :rtype: list of (name, value) pairs
00548         """
00549         args = []
00550         parameters = yaml.load(interaction_parameters)  # convert from yaml string into python dictionary
00551         if parameters is not None:
00552             if type(parameters) is types.DictType:
00553                 for name, value in parameters.items():
00554                     if type(value) is types.DictType or type(value) is types.ListType:
00555                         console.logwarn("Ignoring invalid parameter for roslaunch arg (simple key-value pairs only) [%s][%s]" % (name, value))
00556                     else:
00557                         args.append((name, value))
00558             else:
00559                 console.logwarn("Ignoring invalid parameters for roslaunch args (must be a simple key-value dict) [%s]" % parameters)
00560         return args


rocon_remocon
Author(s): Daniel Stonier, Donguk Lee
autogenerated on Fri Feb 12 2016 02:50:18