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 import rospy
00035 import sys
00036 
00037 from socket import error
00038 
00039 from tornado.ioloop import IOLoop
00040 from tornado.ioloop import PeriodicCallback
00041 from tornado.web import Application
00042 
00043 from rosbridge_server import RosbridgeWebSocket
00044 
00045 
00046 def shutdown_hook():
00047     IOLoop.instance().stop()
00048 
00049 if __name__ == "__main__":
00050     rospy.init_node("rosbridge_websocket")
00051     rospy.on_shutdown(shutdown_hook)    # register shutdown hook to stop the server
00052 
00053     # SSL options
00054     certfile = rospy.get_param('~certfile', None)
00055     keyfile = rospy.get_param('~keyfile', None)
00056     # if authentication should be used
00057     RosbridgeWebSocket.authenticate = rospy.get_param('~authenticate', False)
00058     port = rospy.get_param('~port', 9090)
00059     address = rospy.get_param('~address', "")
00060 
00061     if "--port" in sys.argv:
00062         idx = sys.argv.index("--port")+1
00063         if idx < len(sys.argv):
00064             port = int(sys.argv[idx])
00065         else:
00066             print "--port argument provided without a value."
00067             sys.exit(-1)
00068 
00069     application = Application([(r"/", RosbridgeWebSocket), (r"", RosbridgeWebSocket)])
00070 
00071     connected = False
00072     while(not connected):
00073         try:
00074             if certfile is not None and keyfile is not None:
00075                 application.listen(port, address, ssl_options={ "certfile": certfile, "keyfile": keyfile})
00076             else:
00077                 application.listen(port, address)
00078             rospy.loginfo("Rosbridge WebSocket server started on port %d", port)
00079             connected = True
00080         except error as e:
00081             rospy.logwarn("Unable to start server: " + str(e) + " Retrying in 2s.")
00082             rospy.sleep(2.)
00083 
00084     IOLoop.instance().start()


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Thu Aug 27 2015 14:50:40