rosbridge_websocket.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2012, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of Willow Garage, Inc. nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 
34 from __future__ import print_function
35 import rospy
36 import sys
37 
38 from socket import error
39 
40 from tornado.ioloop import IOLoop
41 from tornado.ioloop import PeriodicCallback
42 from tornado.web import Application
43 
44 from rosbridge_server import RosbridgeWebSocket, ClientManager
45 
46 from rosbridge_library.capabilities.advertise import Advertise
48 from rosbridge_library.capabilities.subscribe import Subscribe
49 from rosbridge_library.capabilities.advertise_service import AdvertiseService
50 from rosbridge_library.capabilities.unadvertise_service import UnadvertiseService
51 from rosbridge_library.capabilities.call_service import CallService
52 
53 
55  IOLoop.instance().stop()
56 
57 if __name__ == "__main__":
58  rospy.init_node("rosbridge_websocket")
59  rospy.on_shutdown(shutdown_hook) # register shutdown hook to stop the server
60 
61  ##################################################
62  # Parameter handling #
63  ##################################################
64  retry_startup_delay = rospy.get_param('~retry_startup_delay', 2.0) # seconds
65 
66  RosbridgeWebSocket.use_compression = rospy.get_param('~use_compression', False)
67 
68  # get RosbridgeProtocol parameters
69  RosbridgeWebSocket.fragment_timeout = rospy.get_param('~fragment_timeout',
70  RosbridgeWebSocket.fragment_timeout)
71  RosbridgeWebSocket.delay_between_messages = rospy.get_param('~delay_between_messages',
72  RosbridgeWebSocket.delay_between_messages)
73  RosbridgeWebSocket.max_message_size = rospy.get_param('~max_message_size',
74  RosbridgeWebSocket.max_message_size)
75  RosbridgeWebSocket.unregister_timeout = rospy.get_param('~unregister_timeout',
76  RosbridgeWebSocket.unregister_timeout)
77  bson_only_mode = rospy.get_param('~bson_only_mode', False)
78 
79  if RosbridgeWebSocket.max_message_size == "None":
80  RosbridgeWebSocket.max_message_size = None
81 
82  # SSL options
83  certfile = rospy.get_param('~certfile', None)
84  keyfile = rospy.get_param('~keyfile', None)
85  # if authentication should be used
86  RosbridgeWebSocket.authenticate = rospy.get_param('~authenticate', False)
87  port = rospy.get_param('~port', 9090)
88  address = rospy.get_param('~address', "")
89 
90  RosbridgeWebSocket.client_manager = ClientManager()
91 
92  # Get the glob strings and parse them as arrays.
93  RosbridgeWebSocket.topics_glob = [
94  element.strip().strip("'")
95  for element in rospy.get_param('~topics_glob', '')[1:-1].split(',')
96  if len(element.strip().strip("'")) > 0]
97  RosbridgeWebSocket.services_glob = [
98  element.strip().strip("'")
99  for element in rospy.get_param('~services_glob', '')[1:-1].split(',')
100  if len(element.strip().strip("'")) > 0]
101  RosbridgeWebSocket.params_glob = [
102  element.strip().strip("'")
103  for element in rospy.get_param('~params_glob', '')[1:-1].split(',')
104  if len(element.strip().strip("'")) > 0]
105 
106  if "--port" in sys.argv:
107  idx = sys.argv.index("--port")+1
108  if idx < len(sys.argv):
109  port = int(sys.argv[idx])
110  else:
111  print("--port argument provided without a value.")
112  sys.exit(-1)
113 
114  if "--address" in sys.argv:
115  idx = sys.argv.index("--address")+1
116  if idx < len(sys.argv):
117  address = int(sys.argv[idx])
118  else:
119  print("--address argument provided without a value.")
120  sys.exit(-1)
121 
122  if "--retry_startup_delay" in sys.argv:
123  idx = sys.argv.index("--retry_startup_delay") + 1
124  if idx < len(sys.argv):
125  retry_startup_delay = int(sys.argv[idx])
126  else:
127  print("--retry_startup_delay argument provided without a value.")
128  sys.exit(-1)
129 
130  if "--fragment_timeout" in sys.argv:
131  idx = sys.argv.index("--fragment_timeout") + 1
132  if idx < len(sys.argv):
133  RosbridgeWebSocket.fragment_timeout = int(sys.argv[idx])
134  else:
135  print("--fragment_timeout argument provided without a value.")
136  sys.exit(-1)
137 
138  if "--delay_between_messages" in sys.argv:
139  idx = sys.argv.index("--delay_between_messages") + 1
140  if idx < len(sys.argv):
141  RosbridgeWebSocket.delay_between_messages = float(sys.argv[idx])
142  else:
143  print("--delay_between_messages argument provided without a value.")
144  sys.exit(-1)
145 
146  if "--max_message_size" in sys.argv:
147  idx = sys.argv.index("--max_message_size") + 1
148  if idx < len(sys.argv):
149  value = sys.argv[idx]
150  if value == "None":
151  RosbridgeWebSocket.max_message_size = None
152  else:
153  RosbridgeWebSocket.max_message_size = int(value)
154  else:
155  print("--max_message_size argument provided without a value. (can be None or <Integer>)")
156  sys.exit(-1)
157 
158  if "--unregister_timeout" in sys.argv:
159  idx = sys.argv.index("--unregister_timeout") + 1
160  if idx < len(sys.argv):
161  unregister_timeout = float(sys.argv[idx])
162  else:
163  print("--unregister_timeout argument provided without a value.")
164  sys.exit(-1)
165 
166  if "--topics_glob" in sys.argv:
167  idx = sys.argv.index("--topics_glob") + 1
168  if idx < len(sys.argv):
169  value = sys.argv[idx]
170  if value == "None":
171  RosbridgeWebSocket.topics_glob = []
172  else:
173  RosbridgeWebSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
174  else:
175  print("--topics_glob argument provided without a value. (can be None or a list)")
176  sys.exit(-1)
177 
178  if "--services_glob" in sys.argv:
179  idx = sys.argv.index("--services_glob") + 1
180  if idx < len(sys.argv):
181  value = sys.argv[idx]
182  if value == "None":
183  RosbridgeWebSocket.services_glob = []
184  else:
185  RosbridgeWebSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
186  else:
187  print("--services_glob argument provided without a value. (can be None or a list)")
188  sys.exit(-1)
189 
190  if "--params_glob" in sys.argv:
191  idx = sys.argv.index("--params_glob") + 1
192  if idx < len(sys.argv):
193  value = sys.argv[idx]
194  if value == "None":
195  RosbridgeWebSocket.params_glob = []
196  else:
197  RosbridgeWebSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
198  else:
199  print("--params_glob argument provided without a value. (can be None or a list)")
200  sys.exit(-1)
201 
202  if ("--bson_only_mode" in sys.argv) or bson_only_mode:
203  RosbridgeWebSocket.bson_only_mode = bson_only_mode
204 
205  # To be able to access the list of topics and services, you must be able to access the rosapi services.
206  if RosbridgeWebSocket.services_glob:
207  RosbridgeWebSocket.services_glob.append("/rosapi/*")
208 
209  Subscribe.topics_glob = RosbridgeWebSocket.topics_glob
210  Advertise.topics_glob = RosbridgeWebSocket.topics_glob
211  Publish.topics_glob = RosbridgeWebSocket.topics_glob
212  AdvertiseService.services_glob = RosbridgeWebSocket.services_glob
213  UnadvertiseService.services_glob = RosbridgeWebSocket.services_glob
214  CallService.services_glob = RosbridgeWebSocket.services_glob
215 
216  ##################################################
217  # Done with parameter handling #
218  ##################################################
219 
220  application = Application([(r"/", RosbridgeWebSocket), (r"", RosbridgeWebSocket)])
221 
222  connected = False
223  while not connected and not rospy.is_shutdown():
224  try:
225  if certfile is not None and keyfile is not None:
226  application.listen(port, address, ssl_options={ "certfile": certfile, "keyfile": keyfile})
227  else:
228  application.listen(port, address)
229  rospy.loginfo("Rosbridge WebSocket server started on port %d", port)
230  connected = True
231  except error as e:
232  rospy.logwarn("Unable to start server: " + str(e) +
233  " Retrying in " + str(retry_startup_delay) + "s.")
234  rospy.sleep(retry_startup_delay)
235 
236  IOLoop.instance().start()


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Fri May 10 2019 02:17:05