rosbridge_tcp.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from __future__ import print_function
4 from rospy import init_node, get_param, loginfo, logerr, on_shutdown, Publisher
5 from rosbridge_server import RosbridgeTcpSocket
6 
10 from rosbridge_library.capabilities.advertise_service import AdvertiseService
11 from rosbridge_library.capabilities.unadvertise_service import UnadvertiseService
12 from rosbridge_library.capabilities.call_service import CallService
13 
14 from functools import partial
15 from signal import signal, SIGINT, SIG_DFL
16 from std_msgs.msg import Int32
17 
18 try:
19  import SocketServer
20 except ImportError:
21  import socketserver as SocketServer
22 
23 import sys
24 import time
25 
26 #TODO: take care of socket timeouts and make sure to close sockets after killing programm to release network ports
27 
28 #TODO: add new parameters to websocket version! those of rosbridge_tcp.py might not be needed, but the others should work well when adding them to .._websocket.py
29 
30 
31 def shutdown_hook(server):
32  server.shutdown()
33 
34 if __name__ == "__main__":
35  loaded = False
36  retry_count = 0
37  while not loaded:
38  retry_count += 1
39  print("trying to start rosbridge TCP server..")
40  try:
41  print("")
42  init_node("rosbridge_tcp")
43  signal(SIGINT, SIG_DFL)
44 
45  """
46  Parameter handling:
47  - try to get parameter from parameter server (..define those via launch-file)
48  - overwrite value if given as commandline-parameter
49 
50  BEGIN...
51  """
52 
53 #TODO: ensure types get cast correctly after getting from parameter server
54 #TODO: check if ROS parameter server uses None string for 'None-value' or Null or something else, then change code accordingly
55 
56  # update parameters from parameter server or use default value ( second parameter of get_param )
57  port = get_param('~port', 9090)
58  host = get_param('~host', '')
59  incoming_buffer = get_param('~incoming_buffer', RosbridgeTcpSocket.incoming_buffer)
60  socket_timeout = get_param('~socket_timeout', RosbridgeTcpSocket.socket_timeout)
61  retry_startup_delay = get_param('~retry_startup_delay', 5.0) # seconds
62  fragment_timeout = get_param('~fragment_timeout', RosbridgeTcpSocket.fragment_timeout)
63  delay_between_messages = get_param('~delay_between_messages', RosbridgeTcpSocket.delay_between_messages)
64  max_message_size = get_param('~max_message_size', RosbridgeTcpSocket.max_message_size)
65  unregister_timeout = get_param('~unregister_timeout', RosbridgeTcpSocket.unregister_timeout)
66  bson_only_mode = get_param('~bson_only_mode', False)
67 
68  if max_message_size == "None":
69  max_message_size = None
70 
71  # Get the glob strings and parse them as arrays.
72  RosbridgeTcpSocket.topics_glob = [
73  element.strip().strip("'")
74  for element in get_param('~topics_glob', '')[1:-1].split(',')
75  if len(element.strip().strip("'")) > 0]
76  RosbridgeTcpSocket.services_glob = [
77  element.strip().strip("'")
78  for element in get_param('~services_glob', '')[1:-1].split(',')
79  if len(element.strip().strip("'")) > 0]
80  RosbridgeTcpSocket.params_glob = [
81  element.strip().strip("'")
82  for element in get_param('~params_glob', '')[1:-1].split(',')
83  if len(element.strip().strip("'")) > 0]
84 
85  # Publisher for number of connected clients
86  RosbridgeTcpSocket.client_count_pub = Publisher('client_count', Int32, queue_size=10, latch=True)
87  RosbridgeTcpSocket.client_count_pub.publish(0)
88 
89  # update parameters if provided via commandline
90  # .. could implemented 'better' (value/type checking, etc.. )
91  if "--port" in sys.argv:
92  idx = sys.argv.index("--port") + 1
93  if idx < len(sys.argv):
94  port = int(sys.argv[idx])
95  else:
96  print("--port argument provided without a value.")
97  sys.exit(-1)
98 
99  if "--host" in sys.argv:
100  idx = sys.argv.index("--host") + 1
101  if idx < len(sys.argv):
102  host = str(sys.argv[idx])
103  else:
104  print("--host argument provided without a value.")
105  sys.exit(-1)
106 
107  if "--incoming_buffer" in sys.argv:
108  idx = sys.argv.index("--incoming_buffer") + 1
109  if idx < len(sys.argv):
110  incoming_buffer = int(sys.argv[idx])
111  else:
112  print("--incoming_buffer argument provided without a value.")
113  sys.exit(-1)
114 
115  if "--socket_timeout" in sys.argv:
116  idx = sys.argv.index("--socket_timeout") + 1
117  if idx < len(sys.argv):
118  socket_timeout = int(sys.argv[idx])
119  else:
120  print("--socket_timeout argument provided without a value.")
121  sys.exit(-1)
122 
123  if "--retry_startup_delay" in sys.argv:
124  idx = sys.argv.index("--retry_startup_delay") + 1
125  if idx < len(sys.argv):
126  retry_startup_delay = int(sys.argv[idx])
127  else:
128  print("--retry_startup_delay argument provided without a value.")
129  sys.exit(-1)
130 
131  if "--fragment_timeout" in sys.argv:
132  idx = sys.argv.index("--fragment_timeout") + 1
133  if idx < len(sys.argv):
134  fragment_timeout = int(sys.argv[idx])
135  else:
136  print("--fragment_timeout argument provided without a value.")
137  sys.exit(-1)
138 
139  if "--delay_between_messages" in sys.argv:
140  idx = sys.argv.index("--delay_between_messages") + 1
141  if idx < len(sys.argv):
142  delay_between_messages = float(sys.argv[idx])
143  else:
144  print("--delay_between_messages argument provided without a value.")
145  sys.exit(-1)
146 
147  if "--max_message_size" in sys.argv:
148  idx = sys.argv.index("--max_message_size") + 1
149  if idx < len(sys.argv):
150  value = sys.argv[idx]
151  if value == "None":
152  max_message_size = None
153  else:
154  max_message_size = int(value)
155  else:
156  print("--max_message_size argument provided without a value. (can be None or <Integer>)")
157  sys.exit(-1)
158 
159  if "--unregister_timeout" in sys.argv:
160  idx = sys.argv.index("--unregister_timeout") + 1
161  if idx < len(sys.argv):
162  unregister_timeout = float(sys.argv[idx])
163  else:
164  print("--unregister_timeout argument provided without a value.")
165  sys.exit(-1)
166 
167  # export parameters to handler class
168  RosbridgeTcpSocket.incoming_buffer = incoming_buffer
169  RosbridgeTcpSocket.socket_timeout = socket_timeout
170  RosbridgeTcpSocket.fragment_timeout = fragment_timeout
171  RosbridgeTcpSocket.delay_between_messages = delay_between_messages
172  RosbridgeTcpSocket.max_message_size = max_message_size
173  RosbridgeTcpSocket.unregister_timeout = unregister_timeout
174  RosbridgeTcpSocket.bson_only_mode = bson_only_mode
175 
176 
177  if "--topics_glob" in sys.argv:
178  idx = sys.argv.index("--topics_glob") + 1
179  if idx < len(sys.argv):
180  value = sys.argv[idx]
181  if value == "None":
182  RosbridgeTcpSocket.topics_glob = []
183  else:
184  RosbridgeTcpSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
185  else:
186  print("--topics_glob argument provided without a value. (can be None or a list)")
187  sys.exit(-1)
188 
189  if "--services_glob" in sys.argv:
190  idx = sys.argv.index("--services_glob") + 1
191  if idx < len(sys.argv):
192  value = sys.argv[idx]
193  if value == "None":
194  RosbridgeTcpSocket.services_glob = []
195  else:
196  RosbridgeTcpSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
197  else:
198  print("--services_glob argument provided without a value. (can be None or a list)")
199  sys.exit(-1)
200 
201  if "--params_glob" in sys.argv:
202  idx = sys.argv.index("--params_glob") + 1
203  if idx < len(sys.argv):
204  value = sys.argv[idx]
205  if value == "None":
206  RosbridgeTcpSocket.params_glob = []
207  else:
208  RosbridgeTcpSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
209  else:
210  print("--params_glob argument provided without a value. (can be None or a list)")
211  sys.exit(-1)
212 
213  if "--bson_only_mode" in sys.argv:
214  bson_only_mode = True
215 
216  # To be able to access the list of topics and services, you must be able to access the rosapi services.
217  if RosbridgeTcpSocket.services_glob:
218  RosbridgeTcpSocket.services_glob.append("/rosapi/*")
219 
220  Subscribe.topics_glob = RosbridgeTcpSocket.topics_glob
221  Advertise.topics_glob = RosbridgeTcpSocket.topics_glob
222  Publish.topics_glob = RosbridgeTcpSocket.topics_glob
223  AdvertiseService.services_glob = RosbridgeTcpSocket.services_glob
224  UnadvertiseService.services_glob = RosbridgeTcpSocket.services_glob
225  CallService.services_glob = RosbridgeTcpSocket.services_glob
226 
227  """
228  ...END (parameter handling)
229  """
230 
231 
232  # Server host is a tuple ('host', port)
233  # empty string for host makes server listen on all available interfaces
234  SocketServer.ThreadingTCPServer.allow_reuse_address = True
235  server = SocketServer.ThreadingTCPServer((host, port), RosbridgeTcpSocket)
236  on_shutdown(partial(shutdown_hook, server))
237 
238  loginfo("Rosbridge TCP server started on port %d", port)
239 
240  server.serve_forever()
241  loaded = True
242  except Exception as e:
243  time.sleep(retry_startup_delay)
244  print("server loaded")
def shutdown_hook(server)


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Wed Jun 3 2020 03:55:18