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