def init_rosbridge(): # Prep RosBrige Handler rospy.init_node("rosbridge_websocket", disable_signals=True) LabRosbridgeWebSocket.client_manager = ClientManager() # Get the glob strings and parse them as arrays. LabRosbridgeWebSocket.topics_glob = [] LabRosbridgeWebSocket.services_glob = ["/rosapi/*"] LabRosbridgeWebSocket.params_glob = [] Subscribe.topics_glob = LabRosbridgeWebSocket.topics_glob Advertise.topics_glob = LabRosbridgeWebSocket.topics_glob Publish.topics_glob = LabRosbridgeWebSocket.topics_glob AdvertiseService.services_glob = LabRosbridgeWebSocket.services_glob UnadvertiseService.services_glob = LabRosbridgeWebSocket.services_glob CallService.services_glob = LabRosbridgeWebSocket.services_glob return LabRosbridgeWebSocket
def start(cls): print("[BRIDGE]: starting") cont = 0 while cont < 10 and (not rosgraph.is_master_online()): time.sleep(1) cont += 1 if rosgraph.is_master_online(): rospy.init_node("rosbridge_websocket", disable_signals=True) cls.client_manager = ClientManager() #if cls.first : # rospy.init_node("rosbridge_websocket", disable_signals=True) # cls.client_manager = ClientManager() # cls.first = False print("[BRIDGE]: running") cls.master = True else: print("[BRIDGE]: master not running") cls.master = False
RosbridgeWebSocket.unregister_timeout = rospy.get_param( '~unregister_timeout', RosbridgeWebSocket.unregister_timeout) bson_only_mode = rospy.get_param('~bson_only_mode', False) if RosbridgeWebSocket.max_message_size == "None": RosbridgeWebSocket.max_message_size = None ping_interval = float(rospy.get_param('~websocket_ping_interval', 0)) ping_timeout = float(rospy.get_param('~websocket_ping_timeout', 30)) port = rospy.get_param('~port', 8080) address = rospy.get_param('~address', "0.0.0.0") external_port = int(rospy.get_param('~websocket_external_port', port)) RosbridgeWebSocket.client_manager = ClientManager() # Get the glob strings and parse them as arrays. RosbridgeWebSocket.topics_glob = [ element.strip().strip("'") for element in rospy.get_param('~topics_glob', '')[1:-1].split(',') if len(element.strip().strip("'")) > 0 ] RosbridgeWebSocket.services_glob = [ element.strip().strip("'") for element in rospy.get_param('~services_glob', '')[1:-1].split(',') if len(element.strip().strip("'")) > 0 ] RosbridgeWebSocket.params_glob = [ element.strip().strip("'") for element in rospy.get_param('~params_glob', '')[1:-1].split(',')
def __init__(self): super().__init__('rosbridge_websocket') RosbridgeWebSocket.node_handle = self ################################################## # Parameter handling # ################################################## retry_startup_delay = self.declare_parameter('retry_startup_delay', 2.0).value # seconds. RosbridgeWebSocket.use_compression = self.declare_parameter( 'use_compression', False).value # get RosbridgeProtocol parameters RosbridgeWebSocket.fragment_timeout = self.declare_parameter( 'fragment_timeout', RosbridgeWebSocket.fragment_timeout).value RosbridgeWebSocket.delay_between_messages = self.declare_parameter( 'delay_between_messages', RosbridgeWebSocket.delay_between_messages).value RosbridgeWebSocket.max_message_size = self.declare_parameter( 'max_message_size', RosbridgeWebSocket.max_message_size).value RosbridgeWebSocket.unregister_timeout = self.declare_parameter( 'unregister_timeout', RosbridgeWebSocket.unregister_timeout).value bson_only_mode = self.declare_parameter('bson_only_mode', False).value if RosbridgeWebSocket.max_message_size == "None": RosbridgeWebSocket.max_message_size = None # get tornado application parameters tornado_settings = {} tornado_settings['websocket_ping_interval'] = float( self.declare_parameter('websocket_ping_interval', 0).value) tornado_settings['websocket_ping_timeout'] = float( self.declare_parameter('websocket_ping_timeout', 30).value) # SSL options certfile = self.declare_parameter('certfile').value keyfile = self.declare_parameter('keyfile').value # if authentication should be used RosbridgeWebSocket.authenticate = self.declare_parameter( 'authenticate', False).value port = self.declare_parameter('port', 9090).value address = self.declare_parameter('address', '').value RosbridgeWebSocket.client_manager = ClientManager(self) # Publisher for number of connected clients # QoS profile with transient local durability (latched topic in ROS 1). client_count_qos_profile = QoSProfile( depth=10, durability=QoSDurabilityPolicy. RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) RosbridgeWebSocket.client_count_pub = self.create_publisher( Int32, 'client_count', qos_profile=client_count_qos_profile) RosbridgeWebSocket.client_count_pub.publish(Int32(data=0)) # Get the glob strings and parse them as arrays. topics_glob = self.declare_parameter('topics_glob', '').value services_glob = self.declare_parameter('services_glob', '').value params_glob = self.declare_parameter('params_glob', '').value RosbridgeWebSocket.topics_glob = [ element.strip().strip("'") for element in topics_glob[1:-1].split(',') if len(element.strip().strip("'")) > 0 ] RosbridgeWebSocket.services_glob = [ element.strip().strip("'") for element in services_glob[1:-1].split(',') if len(element.strip().strip("'")) > 0 ] RosbridgeWebSocket.params_glob = [ element.strip().strip("'") for element in params_glob[1:-1].split(',') if len(element.strip().strip("'")) > 0 ] if "--port" in sys.argv: idx = sys.argv.index("--port") + 1 if idx < len(sys.argv): port = int(sys.argv[idx]) else: print("--port argument provided without a value.") sys.exit(-1) if "--address" in sys.argv: idx = sys.argv.index("--address") + 1 if idx < len(sys.argv): address = int(sys.argv[idx]) else: print("--address argument provided without a value.") sys.exit(-1) if "--retry_startup_delay" in sys.argv: idx = sys.argv.index("--retry_startup_delay") + 1 if idx < len(sys.argv): retry_startup_delay = int(sys.argv[idx]) else: print( "--retry_startup_delay argument provided without a value.") sys.exit(-1) if "--fragment_timeout" in sys.argv: idx = sys.argv.index("--fragment_timeout") + 1 if idx < len(sys.argv): RosbridgeWebSocket.fragment_timeout = int(sys.argv[idx]) else: print("--fragment_timeout argument provided without a value.") sys.exit(-1) if "--delay_between_messages" in sys.argv: idx = sys.argv.index("--delay_between_messages") + 1 if idx < len(sys.argv): RosbridgeWebSocket.delay_between_messages = float( sys.argv[idx]) else: print( "--delay_between_messages argument provided without a value." ) sys.exit(-1) if "--max_message_size" in sys.argv: idx = sys.argv.index("--max_message_size") + 1 if idx < len(sys.argv): value = sys.argv[idx] if value == "None": RosbridgeWebSocket.max_message_size = None else: RosbridgeWebSocket.max_message_size = int(value) else: print( "--max_message_size argument provided without a value. (can be None or <Integer>)" ) sys.exit(-1) if "--unregister_timeout" in sys.argv: idx = sys.argv.index("--unregister_timeout") + 1 if idx < len(sys.argv): unregister_timeout = float(sys.argv[idx]) else: print( "--unregister_timeout argument provided without a value.") sys.exit(-1) if "--topics_glob" in sys.argv: idx = sys.argv.index("--topics_glob") + 1 if idx < len(sys.argv): value = sys.argv[idx] if value == "None": RosbridgeWebSocket.topics_glob = [] else: RosbridgeWebSocket.topics_glob = [ element.strip().strip("'") for element in value[1:-1].split(',') ] else: print( "--topics_glob argument provided without a value. (can be None or a list)" ) sys.exit(-1) if "--services_glob" in sys.argv: idx = sys.argv.index("--services_glob") + 1 if idx < len(sys.argv): value = sys.argv[idx] if value == "None": RosbridgeWebSocket.services_glob = [] else: RosbridgeWebSocket.services_glob = [ element.strip().strip("'") for element in value[1:-1].split(',') ] else: print( "--services_glob argument provided without a value. (can be None or a list)" ) sys.exit(-1) if "--params_glob" in sys.argv: idx = sys.argv.index("--params_glob") + 1 if idx < len(sys.argv): value = sys.argv[idx] if value == "None": RosbridgeWebSocket.params_glob = [] else: RosbridgeWebSocket.params_glob = [ element.strip().strip("'") for element in value[1:-1].split(',') ] else: print( "--params_glob argument provided without a value. (can be None or a list)" ) sys.exit(-1) if ("--bson_only_mode" in sys.argv) or bson_only_mode: RosbridgeWebSocket.bson_only_mode = bson_only_mode if "--websocket_ping_interval" in sys.argv: idx = sys.argv.index("--websocket_ping_interval") + 1 if idx < len(sys.argv): tornado_settings['websocket_ping_interval'] = float( sys.argv[idx]) else: print( "--websocket_ping_interval argument provided without a value." ) sys.exit(-1) if "--websocket_ping_timeout" in sys.argv: idx = sys.argv.index("--websocket_ping_timeout") + 1 if idx < len(sys.argv): tornado_settings['websocket_ping_timeout'] = float( sys.argv[idx]) else: print( "--websocket_ping_timeout argument provided without a value." ) sys.exit(-1) # To be able to access the list of topics and services, you must be able to access the rosapi services. if RosbridgeWebSocket.services_glob: RosbridgeWebSocket.services_glob.append("/rosapi/*") Subscribe.topics_glob = RosbridgeWebSocket.topics_glob Advertise.topics_glob = RosbridgeWebSocket.topics_glob Publish.topics_glob = RosbridgeWebSocket.topics_glob AdvertiseService.services_glob = RosbridgeWebSocket.services_glob UnadvertiseService.services_glob = RosbridgeWebSocket.services_glob CallService.services_glob = RosbridgeWebSocket.services_glob ################################################## # Done with parameter handling # ################################################## application = Application([(r"/", RosbridgeWebSocket), (r"", RosbridgeWebSocket)], **tornado_settings) connected = False while not connected and self.context.ok(): try: if certfile is not None and keyfile is not None: application.listen(port, address, ssl_options={ "certfile": certfile, "keyfile": keyfile }) else: application.listen(port, address) self.get_logger().info( "Rosbridge WebSocket server started on port {}".format( port)) connected = True except error as e: self.get_logger().warn("Unable to start server: {} " "Retrying in {}s.".format( e, retry_startup_delay)) time.sleep(retry_startup_delay)