rosbridge_udp.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2012, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 import rospy
00035 import sys
00036 
00037 from socket import error
00038 from twisted.internet import reactor
00039 from rosbridge_server import RosbridgeUdpSocket,RosbridgeUdpFactory
00040 
00041 from rosbridge_library.capabilities.advertise import Advertise
00042 from rosbridge_library.capabilities.publish import Publish
00043 from rosbridge_library.capabilities.subscribe import Subscribe
00044 from rosbridge_library.capabilities.advertise_service import AdvertiseService
00045 from rosbridge_library.capabilities.unadvertise_service import UnadvertiseService
00046 from rosbridge_library.capabilities.call_service import CallService
00047 
00048 def shutdown_hook():
00049     reactor.stop()
00050 
00051 if __name__ == "__main__":
00052     rospy.init_node("rosbridge_websocket")
00053     rospy.on_shutdown(shutdown_hook)    # register shutdown hook to stop the server
00054 
00055     ##################################################
00056     # Parameter handling                             #
00057     ##################################################
00058      # get RosbridgeProtocol parameters
00059     RosbridgeUdpSocket.fragment_timeout = rospy.get_param('~fragment_timeout',
00060                                                           RosbridgeUdpSocket.fragment_timeout)
00061     RosbridgeUdpSocket.delay_between_messages = rospy.get_param('~delay_between_messages',
00062                                                                 RosbridgeUdpSocket.delay_between_messages)
00063     RosbridgeUdpSocket.max_message_size = rospy.get_param('~max_message_size',
00064                                                           RosbridgeUdpSocket.max_message_size)
00065     if RosbridgeUdpSocket.max_message_size == "None":
00066         RosbridgeUdpSocket.max_message_size = None
00067 
00068     # Get the glob strings and parse them as arrays.
00069     RosbridgeUdpSocket.topics_glob = [
00070         element.strip().strip("'")
00071         for element in rospy.get_param('~topics_glob', '')[1:-1].split(',')
00072         if len(element.strip().strip("'")) > 0]
00073     RosbridgeUdpSocket.services_glob = [
00074         element.strip().strip("'")
00075         for element in rospy.get_param('~services_glob', '')[1:-1].split(',')
00076         if len(element.strip().strip("'")) > 0]
00077     RosbridgeUdpSocket.params_glob = [
00078         element.strip().strip("'")
00079         for element in rospy.get_param('~params_glob', '')[1:-1].split(',')
00080         if len(element.strip().strip("'")) > 0]
00081 
00082     # if authentication should be used
00083     RosbridgeUdpSocket.authenticate = rospy.get_param('~authenticate', False)
00084     port = rospy.get_param('~port', 9090)
00085     interface = rospy.get_param('~interface', "")
00086 
00087     if "--port" in sys.argv:
00088         idx = sys.argv.index("--port")+1
00089         if idx < len(sys.argv):
00090             port = int(sys.argv[idx])
00091         else:
00092             print "--port argument provided without a value."
00093             sys.exit(-1)
00094 
00095     if "--interface" in sys.argv:
00096         idx = sys.argv.index("--interface")+1
00097         if idx < len(sys.argv):
00098             interface = int(sys.argv[idx])
00099         else:
00100             print "--interface argument provided without a value."
00101             sys.exit(-1)
00102 
00103     if "--fragment_timeout" in sys.argv:
00104         idx = sys.argv.index("--fragment_timeout") + 1
00105         if idx < len(sys.argv):
00106             RosbridgeUdpSocket.fragment_timeout = int(sys.argv[idx])
00107         else:
00108             print "--fragment_timeout argument provided without a value."
00109             sys.exit(-1)
00110 
00111     if "--delay_between_messages" in sys.argv:
00112         idx = sys.argv.index("--delay_between_messages") + 1
00113         if idx < len(sys.argv):
00114             RosbridgeUdpSocket.delay_between_messages = float(sys.argv[idx])
00115         else:
00116             print "--delay_between_messages argument provided without a value."
00117             sys.exit(-1)
00118 
00119     if "--max_message_size" in sys.argv:
00120         idx = sys.argv.index("--max_message_size") + 1
00121         if idx < len(sys.argv):
00122             value = sys.argv[idx]
00123             if value == "None":
00124                 RosbridgeUdpSocket.max_message_size = None
00125             else:
00126                 RosbridgeUdpSocket.max_message_size = int(value)
00127         else:
00128             print "--max_message_size argument provided without a value. (can be None or <Integer>)"
00129             sys.exit(-1)
00130 
00131     if "--topics_glob" in sys.argv:
00132         idx = sys.argv.index("--topics_glob") + 1
00133         if idx < len(sys.argv):
00134             value = sys.argv[idx]
00135             if value == "None":
00136                 RosbridgeUdpSocket.topics_glob = []
00137             else:
00138                 RosbridgeUdpSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
00139         else:
00140             print "--topics_glob argument provided without a value. (can be None or a list)"
00141             sys.exit(-1)
00142 
00143     if "--services_glob" in sys.argv:
00144         idx = sys.argv.index("--services_glob") + 1
00145         if idx < len(sys.argv):
00146             value = sys.argv[idx]
00147             if value == "None":
00148                 RosbridgeUdpSocket.services_glob = []
00149             else:
00150                 RosbridgeUdpSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
00151         else:
00152             print "--services_glob argument provided without a value. (can be None or a list)"
00153             sys.exit(-1)
00154 
00155     if "--params_glob" in sys.argv:
00156         idx = sys.argv.index("--params_glob") + 1
00157         if idx < len(sys.argv):
00158             value = sys.argv[idx]
00159             if value == "None":
00160                 RosbridgeUdpSocket.params_glob = []
00161             else:
00162                 RosbridgeUdpSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
00163         else:
00164             print "--params_glob argument provided without a value. (can be None or a list)"
00165             sys.exit(-1)
00166 
00167     # To be able to access the list of topics and services, you must be able to access the rosapi services.
00168     if RosbridgeUdpSocket.services_glob:
00169         RosbridgeUdpSocket.services_glob.append("/rosapi/*")
00170 
00171     Subscribe.topics_glob = RosbridgeUdpSocket.topics_glob
00172     Advertise.topics_glob = RosbridgeUdpSocket.topics_glob
00173     Publish.topics_glob = RosbridgeUdpSocket.topics_glob
00174     AdvertiseService.services_glob = RosbridgeUdpSocket.services_glob
00175     UnadvertiseService.services_glob = RosbridgeUdpSocket.services_glob
00176     CallService.services_glob = RosbridgeUdpSocket.services_glob
00177 
00178     ##################################################
00179     # Done with parameter handling                   #
00180     ##################################################
00181 
00182     rospy.loginfo("Rosbridge UDP server started on port %d", port)
00183     reactor.listenUDP(port, RosbridgeUdpFactory(), interface=interface)
00184     reactor.run()


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Wed Sep 13 2017 03:18:20