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 import os
00036 import sys
00037 import socket
00038 import threading
00039 import traceback
00040 import time
00041 import urlparse
00042 
00043 from rosgraph.xmlrpc import XmlRpcHandler
00044 
00045 import rospy.names
00046 
00047 import rospy.impl.tcpros
00048 
00049 from rospy.core import global_name, is_topic
00050 from rospy.impl.registration import get_topic_manager
00051 from rospy.impl.validators import non_empty, ParameterInvalid
00052 
00053 from rospy.impl.masterslave import apivalidate
00054 
00055 
00056 
00057 
00058 def is_publishers_list(paramName):
00059     return ('is_publishers_list', paramName)
00060 
00061 class ProxyHandler(XmlRpcHandler):
00062 
00063     def __init__(self, name, master_uri, topic_manager, protocol_handlers):
00064         """
00065         Variant handler for proxy
00066         @param name: ROS name of this node
00067         @type  name: str
00068         @param master_uri: URI of master node, or None if this node is the master
00069         @type  master_uri: str
00070         """
00071         super(ProxyHandler, self).__init__()
00072         self.master_uri = master_uri
00073         self.name = name
00074         self.uri = None
00075         self.done = False
00076 
00077         self.protocol_handlers = protocol_handlers
00078             
00079         self.reg_man = None
00080         
00081         
00082         self.topic_man = topic_manager
00083 
00084     
00085     
00086 
00087     def _ready(self, uri):
00088         """
00089         @param uri: XML-RPC URI
00090         @type  uri: str
00091         callback from ROSNode to inform handler of correct i/o information
00092         """
00093         self.uri = uri
00094 
00095     def _custom_validate(self, validation, param_name, param_value, caller_id):
00096         """
00097         Implements validation rules that require access to internal ROSHandler state.
00098         @param validation: name of validation rule to use
00099         @type  validation: str
00100         @param param_name: name of parameter being validated
00101         @type  param_name: str
00102         @param param_value str: value of parameter
00103         @type  param_value: str
00104         @param caller_id: value of caller_id parameter to API method
00105         @type  caller_id: str
00106         @raise ParameterInvalid: if the parameter does not meet validation
00107         @return: new value for parameter, after validation
00108         """
00109         if validation == 'is_publishers_list':
00110             if not type(param_value) == list:
00111                 raise ParameterInvalid("ERROR: param [%s] must be a list"%param_name)
00112             for v in param_value:
00113                 if not isinstance(v, basestring):
00114                     raise ParameterInvalid("ERROR: param [%s] must be a list of strings"%param_name)
00115                 parsed = urlparse.urlparse(v)
00116                 if not parsed[0] or not parsed[1]: 
00117                     raise ParameterInvalid("ERROR: param [%s] does not contain valid URLs [%s]"%(param_name, v))
00118             return param_value
00119         else:
00120             raise ParameterInvalid("ERROR: param [%s] has an unknown validation type [%s]"%(param_name, validation))
00121 
00122     
00123     
00124 
00125     @apivalidate([])
00126     def getBusStats(self, caller_id):
00127         
00128         return 1, '', [[], [], []]
00129 
00130     @apivalidate([])
00131     def getBusInfo(self, caller_id):
00132         
00133         return 1, '', [[], [], []]
00134     
00135     @apivalidate('')
00136     def getMasterUri(self, caller_id):
00137         return 1, self.master_uri, self.master_uri
00138         
00139     @apivalidate(0, (None, ))
00140     def shutdown(self, caller_id, msg=''):
00141         return -1, "not authorized", 0
00142 
00143     @apivalidate(-1)
00144     def getPid(self, caller_id):
00145         return -1, "not authorized", 0
00146 
00147     
00148     
00149 
00150     @apivalidate([])
00151     def getSubscriptions(self, caller_id):
00152         """Retrieve a list of topics that this node subscribes to
00153         @param caller_id: ROS caller id    
00154         @type  caller_id: str
00155         @return [int, str, [ [topic1, topicType1]...[topicN, topicTypeN]]]: list of topics this node subscribes to
00156         """
00157         return 1, "subscriptions", self.topic_man.get_subscriptions()
00158 
00159     @apivalidate([])
00160     def getPublications(self, caller_id):
00161         """
00162         Retrieve a list of topics that this node publishes.
00163         @param caller_id: ROS caller id    
00164         @type  caller_id: str
00165         @return: list of topics published by this node
00166         @rtype: [int, str, [ [topic1, topicType1]...[topicN, topicTypeN]]]
00167         """
00168         return 1, "publications", self.topic_man.get_publications()
00169     
00170     @apivalidate(-1, (global_name('parameter_key'), None))
00171     def paramUpdate(self, caller_id, parameter_key, parameter_value):
00172         """
00173         Callback from master of current publisher list for specified topic.
00174         @param caller_id: ROS caller id
00175         @type  caller_id: str
00176         @param parameter_key str: parameter name, globally resolved
00177         @type  parameter_key: str
00178         @param parameter_value New parameter value
00179         @type  parameter_value: XMLRPC-legal value
00180         @return: [code, status, ignore]. If code is -1 ERROR, the node
00181         is not subscribed to parameter_key
00182         @rtype: [int, str, int]
00183         """
00184         
00185         return -1, 'not authorized', 0
00186 
00187     @apivalidate(-1, (is_topic('topic'), is_publishers_list('publishers')))
00188     def publisherUpdate(self, caller_id, topic, publishers):
00189         """
00190         Callback from master of current publisher list for specified topic.
00191         @param caller_id: ROS caller id
00192         @type  caller_id: str
00193         @param topic str: topic name
00194         @type  topic: str
00195         @param publishers: list of current publishers for topic in the form of XMLRPC URIs
00196         @type  publishers: [str]
00197         @return: [code, status, ignore]
00198         @rtype: [int, str, int]
00199         """
00200         if self.reg_man:
00201             for uri in publishers:
00202                 self.reg_man.publisher_update(topic, publishers)
00203     
00204     @apivalidate([], (is_topic('topic'), non_empty('protocols')))
00205     def requestTopic(self, caller_id, topic, protocols):
00206         """
00207         Publisher node API method called by a subscriber node.
00208    
00209         Request that source allocate a channel for communication. Subscriber provides
00210         a list of desired protocols for communication. Publisher returns the
00211         selected protocol along with any additional params required for
00212         establishing connection. For example, for a TCP/IP-based connection,
00213         the source node may return a port number of TCP/IP server. 
00214         @param caller_id str: ROS caller id    
00215         @type  caller_id: str
00216         @param topic: topic name
00217         @type  topic: str
00218         @param protocols: list of desired
00219          protocols for communication in order of preference. Each
00220          protocol is a list of the form [ProtocolName,
00221          ProtocolParam1, ProtocolParam2...N]
00222         @type  protocols: [[str, XmlRpcLegalValue*]]
00223         @return: [code, msg, protocolParams]. protocolParams may be an
00224         empty list if there are no compatible protocols.
00225         @rtype: [int, str, [str, XmlRpcLegalValue*]]
00226         """
00227         if not self.topic_man.has_publication(topic):
00228             return -1, "Not a publisher of [%s]"%topic, []
00229         for protocol in protocols: 
00230             protocol_id = protocol[0]
00231             for h in self.protocol_handlers:
00232                 if h.supports(protocol_id):
00233                     return h.init_publisher(topic, protocol)
00234         return 0, "no supported protocol implementations", []
00235 
00236