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 from __future__ import print_function
00035 import rospy
00036 import sys
00037
00038 from socket import error
00039 from twisted.internet import reactor
00040 from rosbridge_server import RosbridgeUdpSocket,RosbridgeUdpFactory
00041
00042 from rosbridge_library.capabilities.advertise import Advertise
00043 from rosbridge_library.capabilities.publish import Publish
00044 from rosbridge_library.capabilities.subscribe import Subscribe
00045 from rosbridge_library.capabilities.advertise_service import AdvertiseService
00046 from rosbridge_library.capabilities.unadvertise_service import UnadvertiseService
00047 from rosbridge_library.capabilities.call_service import CallService
00048
00049 def shutdown_hook():
00050 reactor.stop()
00051
00052 if __name__ == "__main__":
00053 rospy.init_node("rosbridge_websocket")
00054 rospy.on_shutdown(shutdown_hook)
00055
00056
00057
00058
00059
00060 RosbridgeUdpSocket.fragment_timeout = rospy.get_param('~fragment_timeout',
00061 RosbridgeUdpSocket.fragment_timeout)
00062 RosbridgeUdpSocket.delay_between_messages = rospy.get_param('~delay_between_messages',
00063 RosbridgeUdpSocket.delay_between_messages)
00064 RosbridgeUdpSocket.max_message_size = rospy.get_param('~max_message_size',
00065 RosbridgeUdpSocket.max_message_size)
00066 if RosbridgeUdpSocket.max_message_size == "None":
00067 RosbridgeUdpSocket.max_message_size = None
00068
00069
00070 RosbridgeUdpSocket.topics_glob = [
00071 element.strip().strip("'")
00072 for element in rospy.get_param('~topics_glob', '')[1:-1].split(',')
00073 if len(element.strip().strip("'")) > 0]
00074 RosbridgeUdpSocket.services_glob = [
00075 element.strip().strip("'")
00076 for element in rospy.get_param('~services_glob', '')[1:-1].split(',')
00077 if len(element.strip().strip("'")) > 0]
00078 RosbridgeUdpSocket.params_glob = [
00079 element.strip().strip("'")
00080 for element in rospy.get_param('~params_glob', '')[1:-1].split(',')
00081 if len(element.strip().strip("'")) > 0]
00082
00083
00084 RosbridgeUdpSocket.authenticate = rospy.get_param('~authenticate', False)
00085 port = rospy.get_param('~port', 9090)
00086 interface = rospy.get_param('~interface', "")
00087
00088 if "--port" in sys.argv:
00089 idx = sys.argv.index("--port")+1
00090 if idx < len(sys.argv):
00091 port = int(sys.argv[idx])
00092 else:
00093 print("--port argument provided without a value.")
00094 sys.exit(-1)
00095
00096 if "--interface" in sys.argv:
00097 idx = sys.argv.index("--interface")+1
00098 if idx < len(sys.argv):
00099 interface = int(sys.argv[idx])
00100 else:
00101 print("--interface argument provided without a value.")
00102 sys.exit(-1)
00103
00104 if "--fragment_timeout" in sys.argv:
00105 idx = sys.argv.index("--fragment_timeout") + 1
00106 if idx < len(sys.argv):
00107 RosbridgeUdpSocket.fragment_timeout = int(sys.argv[idx])
00108 else:
00109 print("--fragment_timeout argument provided without a value.")
00110 sys.exit(-1)
00111
00112 if "--delay_between_messages" in sys.argv:
00113 idx = sys.argv.index("--delay_between_messages") + 1
00114 if idx < len(sys.argv):
00115 RosbridgeUdpSocket.delay_between_messages = float(sys.argv[idx])
00116 else:
00117 print("--delay_between_messages argument provided without a value.")
00118 sys.exit(-1)
00119
00120 if "--max_message_size" in sys.argv:
00121 idx = sys.argv.index("--max_message_size") + 1
00122 if idx < len(sys.argv):
00123 value = sys.argv[idx]
00124 if value == "None":
00125 RosbridgeUdpSocket.max_message_size = None
00126 else:
00127 RosbridgeUdpSocket.max_message_size = int(value)
00128 else:
00129 print("--max_message_size argument provided without a value. (can be None or <Integer>)")
00130 sys.exit(-1)
00131
00132 if "--topics_glob" in sys.argv:
00133 idx = sys.argv.index("--topics_glob") + 1
00134 if idx < len(sys.argv):
00135 value = sys.argv[idx]
00136 if value == "None":
00137 RosbridgeUdpSocket.topics_glob = []
00138 else:
00139 RosbridgeUdpSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
00140 else:
00141 print("--topics_glob argument provided without a value. (can be None or a list)")
00142 sys.exit(-1)
00143
00144 if "--services_glob" in sys.argv:
00145 idx = sys.argv.index("--services_glob") + 1
00146 if idx < len(sys.argv):
00147 value = sys.argv[idx]
00148 if value == "None":
00149 RosbridgeUdpSocket.services_glob = []
00150 else:
00151 RosbridgeUdpSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
00152 else:
00153 print("--services_glob argument provided without a value. (can be None or a list)")
00154 sys.exit(-1)
00155
00156 if "--params_glob" in sys.argv:
00157 idx = sys.argv.index("--params_glob") + 1
00158 if idx < len(sys.argv):
00159 value = sys.argv[idx]
00160 if value == "None":
00161 RosbridgeUdpSocket.params_glob = []
00162 else:
00163 RosbridgeUdpSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
00164 else:
00165 print("--params_glob argument provided without a value. (can be None or a list)")
00166 sys.exit(-1)
00167
00168
00169 if RosbridgeUdpSocket.services_glob:
00170 RosbridgeUdpSocket.services_glob.append("/rosapi/*")
00171
00172 Subscribe.topics_glob = RosbridgeUdpSocket.topics_glob
00173 Advertise.topics_glob = RosbridgeUdpSocket.topics_glob
00174 Publish.topics_glob = RosbridgeUdpSocket.topics_glob
00175 AdvertiseService.services_glob = RosbridgeUdpSocket.services_glob
00176 UnadvertiseService.services_glob = RosbridgeUdpSocket.services_glob
00177 CallService.services_glob = RosbridgeUdpSocket.services_glob
00178
00179
00180
00181
00182
00183 rospy.loginfo("Rosbridge UDP server started on port %d", port)
00184 reactor.listenUDP(port, RosbridgeUdpFactory(), interface=interface)
00185 reactor.run()