protocol.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 
00033 import rospy
00034 import json
00035 
00036 
00037 class InvalidArgumentException(Exception):
00038     pass
00039 
00040 class MissingArgumentException(Exception):
00041     pass
00042 
00043 class Protocol:
00044     """ The interface for a single client to interact with ROS.
00045 
00046     See rosbridge_protocol for the default protocol used by rosbridge
00047 
00048     The lifecycle for a Protocol instance is as follows:
00049     - Pass incoming messages from the client to incoming
00050     - Propagate outgoing messages to the client by overriding outgoing
00051     - Call finish to clean up resources when the client is finished
00052 
00053     """
00054 
00055     def __init__(self, client_id):
00056         """ Keyword arguments:
00057         client_id -- a unique ID for this client to take.  Uniqueness is
00058         important otherwise there will be conflicts between multiple clients
00059         with shared resources
00060 
00061         """
00062         self.client_id = client_id
00063         self.capabilities = []
00064         self.operations = {}
00065 
00066     def incoming(self, message_string):
00067         """ Process an incoming message from the client
00068 
00069         Keyword arguments:
00070         message_string -- the wire-level message sent by the client
00071 
00072         """
00073         msg = self.deserialize(message_string)
00074         if msg is None:
00075             return
00076 
00077         mid = None
00078         if "id" in msg:
00079             mid = msg["id"]
00080 
00081         if "op" not in msg:
00082             if "receiver" in msg:
00083                 self.log("error", "Received a rosbridge v1.0 message.  Please refer to rosbridge.org for the correct format of rosbridge v2.0 messages.  Original message was: %s" % message_string)
00084             else:
00085                 self.log("error", "Received a message without an op.  All messages require 'op' field with value one of: %s.  Original message was: %s" % (self.operations.keys(), message_string), mid)
00086             return
00087 
00088         op = msg["op"]
00089         if op not in self.operations:
00090             self.log("error", "Unknown operation: %s.  Allowed operations: %s" % (op, self.operations.keys()), mid)
00091             return
00092 
00093         try:
00094             self.operations[op](msg)
00095         except Exception as exc:
00096             self.log("error", "%s: %s" % (op, str(exc)), mid)
00097 
00098     def outgoing(self, message):
00099         """ Pass an outgoing message to the client.  This method should be
00100         overridden.
00101 
00102         Keyword arguments:
00103         message -- the wire-level message to send to the client
00104 
00105         """
00106         print "outgoing message"
00107         pass
00108 
00109     def send(self, message, cid=None):
00110         """ Called internally in preparation for sending messages to the client
00111 
00112         This method pre-processes the message then passes it to the overridden
00113         outgoing method.
00114 
00115         Keyword arguments:
00116         message -- a dict of message values to be marshalled and sent
00117         cid     -- (optional) an associated id
00118 
00119         """
00120         serialized = self.serialize(message, cid)
00121         if serialized is not None:
00122             self.outgoing(serialized)
00123 
00124     def finish(self):
00125         """ Indicate that the client is finished and clean up resources.
00126 
00127         All clients should call this method after disconnecting.
00128 
00129         """
00130         for capability in self.capabilities:
00131             capability.finish()
00132 
00133     def serialize(self, msg, cid=None):
00134         """ Turns a dictionary of values into the appropriate wire-level
00135         representation.
00136 
00137         Default behaviour uses JSON.  Override to use a different container.
00138 
00139         Keyword arguments:
00140         msg -- the dictionary of values to serialize
00141         cid -- (optional) an ID associated with this.  Will be logged on err.
00142 
00143         Returns a JSON string representing the dictionary
00144         """
00145         try:
00146             return json.dumps(msg)
00147         except:
00148             if cid is not None:
00149                 # Only bother sending the log message if there's an id
00150                 self.log("error", "Unable to serialize %s message to client"
00151                          % msg["op"], cid)
00152             return None
00153 
00154     def deserialize(self, msg, cid=None):
00155         """ Turns the wire-level representation into a dictionary of values
00156 
00157         Default behaviour assumes JSON. Override to use a different container.
00158 
00159         Keyword arguments:
00160         msg -- the wire-level message to deserialize
00161         cid -- (optional) an ID associated with this.  Is logged on error
00162 
00163         Returns a dictionary of values
00164 
00165         """
00166         try:
00167             return json.loads(msg)
00168         except:
00169             self.log("error",
00170              "Unable to deserialize message from client: %s" % msg, cid)
00171             return None
00172 
00173     def register_operation(self, opcode, handler):
00174         """ Register a handler for an opcode
00175 
00176         Keyword arguments:
00177         opcode  -- the opcode to register this handler for
00178         handler -- a callback function to call for messages with this opcode
00179 
00180         """
00181         self.operations[opcode] = handler
00182 
00183     def unregister_operation(self, opcode):
00184         """ Unregister a handler for an opcode
00185 
00186         Keyword arguments:
00187         opcode -- the opcode to unregister the handler for
00188 
00189         """
00190         if opcode in self.operations:
00191             del self.operations[opcode]
00192 
00193     def add_capability(self, capability_class):
00194         """ Add a capability to the protocol.
00195 
00196         This method is for convenience; assumes the default capability
00197         constructor
00198 
00199         Keyword arguments:
00200         capability_class -- the class of the capability to add
00201 
00202         """
00203         self.capabilities.append(capability_class(self))
00204 
00205     def log(self, level, message, lid=None):
00206         """ Log a message to the client.  By default just sends to stdout
00207 
00208         Keyword arguments:
00209         level   -- the logger level of this message
00210         message -- the string message to send to the user
00211         lid     -- an associated for this log message
00212 
00213         """
00214         stdout_formatted_msg = None
00215         if lid is not None:
00216             stdout_formatted_msg = "[Client %s] [id: %s] %s" % (self.client_id, lid, message)
00217         else:
00218             stdout_formatted_msg = "[Client %s] %s" % (self.client_id, message)
00219 
00220         if level == "error" or level == "err":
00221             rospy.logerr(stdout_formatted_msg)
00222         elif level == "warning" or level == "warn":
00223             rospy.logwarn(stdout_formatted_msg)
00224         elif level == "info" or level == "information":
00225             rospy.loginfo(stdout_formatted_msg)
00226         else:
00227             rospy.logdebug(stdout_formatted_msg)
00228 


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Thu Jan 2 2014 11:53:35