rosbridge_websocket.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 from __future__ import print_function
00035 import rospy
00036 import sys
00037 
00038 from socket import error
00039 
00040 from tornado.ioloop import IOLoop
00041 from tornado.ioloop import PeriodicCallback
00042 from tornado.web import Application
00043 
00044 from rosbridge_server import RosbridgeWebSocket
00045 
00046 from rosbridge_library.capabilities.advertise import Advertise
00047 from rosbridge_library.capabilities.publish import Publish
00048 from rosbridge_library.capabilities.subscribe import Subscribe
00049 from rosbridge_library.capabilities.advertise_service import AdvertiseService
00050 from rosbridge_library.capabilities.unadvertise_service import UnadvertiseService
00051 from rosbridge_library.capabilities.call_service import CallService
00052 
00053 def shutdown_hook():
00054     IOLoop.instance().stop()
00055 
00056 if __name__ == "__main__":
00057     rospy.init_node("rosbridge_websocket")
00058     rospy.on_shutdown(shutdown_hook)    # register shutdown hook to stop the server
00059 
00060     ##################################################
00061     # Parameter handling                             #
00062     ##################################################
00063     retry_startup_delay = rospy.get_param('~retry_startup_delay', 2.0)  # seconds
00064 
00065     # get RosbridgeProtocol parameters
00066     RosbridgeWebSocket.fragment_timeout = rospy.get_param('~fragment_timeout',
00067                                                           RosbridgeWebSocket.fragment_timeout)
00068     RosbridgeWebSocket.delay_between_messages = rospy.get_param('~delay_between_messages',
00069                                                                 RosbridgeWebSocket.delay_between_messages)
00070     RosbridgeWebSocket.max_message_size = rospy.get_param('~max_message_size',
00071                                                           RosbridgeWebSocket.max_message_size)
00072     bson_only_mode = rospy.get_param('~bson_only_mode', False)
00073 
00074     if RosbridgeWebSocket.max_message_size == "None":
00075         RosbridgeWebSocket.max_message_size = None
00076 
00077     # SSL options
00078     certfile = rospy.get_param('~certfile', None)
00079     keyfile = rospy.get_param('~keyfile', None)
00080     # if authentication should be used
00081     RosbridgeWebSocket.authenticate = rospy.get_param('~authenticate', False)
00082     port = rospy.get_param('~port', 9090)
00083     address = rospy.get_param('~address', "")
00084 
00085     # Get the glob strings and parse them as arrays.
00086     RosbridgeWebSocket.topics_glob = [
00087         element.strip().strip("'")
00088         for element in rospy.get_param('~topics_glob', '')[1:-1].split(',')
00089         if len(element.strip().strip("'")) > 0]
00090     RosbridgeWebSocket.services_glob = [
00091         element.strip().strip("'")
00092         for element in rospy.get_param('~services_glob', '')[1:-1].split(',')
00093         if len(element.strip().strip("'")) > 0]
00094     RosbridgeWebSocket.params_glob = [
00095         element.strip().strip("'")
00096         for element in rospy.get_param('~params_glob', '')[1:-1].split(',')
00097         if len(element.strip().strip("'")) > 0]
00098 
00099     if "--port" in sys.argv:
00100         idx = sys.argv.index("--port")+1
00101         if idx < len(sys.argv):
00102             port = int(sys.argv[idx])
00103         else:
00104             print("--port argument provided without a value.")
00105             sys.exit(-1)
00106 
00107     if "--address" in sys.argv:
00108         idx = sys.argv.index("--address")+1
00109         if idx < len(sys.argv):
00110             address = int(sys.argv[idx])
00111         else:
00112             print("--address argument provided without a value.")
00113             sys.exit(-1)
00114 
00115     if "--retry_startup_delay" in sys.argv:
00116         idx = sys.argv.index("--retry_startup_delay") + 1
00117         if idx < len(sys.argv):
00118             retry_startup_delay = int(sys.argv[idx])
00119         else:
00120             print("--retry_startup_delay argument provided without a value.")
00121             sys.exit(-1)
00122 
00123     if "--fragment_timeout" in sys.argv:
00124         idx = sys.argv.index("--fragment_timeout") + 1
00125         if idx < len(sys.argv):
00126             RosbridgeWebSocket.fragment_timeout = int(sys.argv[idx])
00127         else:
00128             print("--fragment_timeout argument provided without a value.")
00129             sys.exit(-1)
00130 
00131     if "--delay_between_messages" in sys.argv:
00132         idx = sys.argv.index("--delay_between_messages") + 1
00133         if idx < len(sys.argv):
00134             RosbridgeWebSocket.delay_between_messages = float(sys.argv[idx])
00135         else:
00136             print("--delay_between_messages argument provided without a value.")
00137             sys.exit(-1)
00138 
00139     if "--max_message_size" in sys.argv:
00140         idx = sys.argv.index("--max_message_size") + 1
00141         if idx < len(sys.argv):
00142             value = sys.argv[idx]
00143             if value == "None":
00144                 RosbridgeWebSocket.max_message_size = None
00145             else:
00146                 RosbridgeWebSocket.max_message_size = int(value)
00147         else:
00148             print("--max_message_size argument provided without a value. (can be None or <Integer>)")
00149             sys.exit(-1)
00150 
00151     if "--topics_glob" in sys.argv:
00152         idx = sys.argv.index("--topics_glob") + 1
00153         if idx < len(sys.argv):
00154             value = sys.argv[idx]
00155             if value == "None":
00156                 RosbridgeWebSocket.topics_glob = []
00157             else:
00158                 RosbridgeWebSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
00159         else:
00160             print("--topics_glob argument provided without a value. (can be None or a list)")
00161             sys.exit(-1)
00162 
00163     if "--services_glob" in sys.argv:
00164         idx = sys.argv.index("--services_glob") + 1
00165         if idx < len(sys.argv):
00166             value = sys.argv[idx]
00167             if value == "None":
00168                 RosbridgeWebSocket.services_glob = []
00169             else:
00170                 RosbridgeWebSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
00171         else:
00172             print("--services_glob argument provided without a value. (can be None or a list)")
00173             sys.exit(-1)
00174 
00175     if "--params_glob" in sys.argv:
00176         idx = sys.argv.index("--params_glob") + 1
00177         if idx < len(sys.argv):
00178             value = sys.argv[idx]
00179             if value == "None":
00180                 RosbridgeWebSocket.params_glob = []
00181             else:
00182                 RosbridgeWebSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
00183         else:
00184             print("--params_glob argument provided without a value. (can be None or a list)")
00185             sys.exit(-1)
00186 
00187     if ("--bson_only_mode" in sys.argv) or bson_only_mode:
00188         print("bson_only_mode is only supported in the TCP Version of Rosbridge currently. Ignoring bson_only_mode argument...")
00189 
00190     # To be able to access the list of topics and services, you must be able to access the rosapi services.
00191     if RosbridgeWebSocket.services_glob:
00192         RosbridgeWebSocket.services_glob.append("/rosapi/*")
00193 
00194     Subscribe.topics_glob = RosbridgeWebSocket.topics_glob
00195     Advertise.topics_glob = RosbridgeWebSocket.topics_glob
00196     Publish.topics_glob = RosbridgeWebSocket.topics_glob
00197     AdvertiseService.services_glob = RosbridgeWebSocket.services_glob
00198     UnadvertiseService.services_glob = RosbridgeWebSocket.services_glob
00199     CallService.services_glob = RosbridgeWebSocket.services_glob
00200 
00201     ##################################################
00202     # Done with parameter handling                   #
00203     ##################################################
00204 
00205     application = Application([(r"/", RosbridgeWebSocket), (r"", RosbridgeWebSocket)])
00206 
00207     connected = False
00208     while not connected and not rospy.is_shutdown():
00209         try:
00210             if certfile is not None and keyfile is not None:
00211                 application.listen(port, address, ssl_options={ "certfile": certfile, "keyfile": keyfile})
00212             else:
00213                 application.listen(port, address)
00214             rospy.loginfo("Rosbridge WebSocket server started on port %d", port)
00215             connected = True
00216         except error as e:
00217             rospy.logwarn("Unable to start server: " + str(e) +
00218                           " Retrying in " + str(retry_startup_delay) + "s.")
00219             rospy.sleep(retry_startup_delay)
00220 
00221     IOLoop.instance().start()


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Thu Jun 6 2019 21:51:50