/// <summary> /// Add a subscriber callback to this connection. There can be many subscribers. /// </summary> /// <typeparam name="Tmsg">Message type used in the callback</typeparam> /// <param name="sub">Subscriber</param> /// <param name="callback">Method to call when a message matching the given subscriber is received</param> public ROSBridgeSubscriber <Tmsg> Subscribe <Tmsg>(string topic, ROSMessageCallback <Tmsg> callback, uint queueSize = 0) where Tmsg : ROSMessage, new() { MessageCallback MessageCallback = (ROSMessage msg) => { Tmsg message = msg as Tmsg; callback(message); }; var getMessageType = typeof(Tmsg).GetMethod("GetMessageType"); if (getMessageType == null) { Debug.LogError("Could not retrieve method GetMessageType() from " + typeof(Tmsg).ToString()); return(null); } string messageType = (string)getMessageType.Invoke(null, null); if (messageType == null) { Debug.LogError("Could not retrieve valid message type from " + typeof(Tmsg).ToString()); return(null); } ROSBridgeSubscriber <Tmsg> subscriber = new ROSBridgeSubscriber <Tmsg>(topic, messageType); this.subscribers.Add(subscriber, MessageCallback); this.msgQueue.Add(subscriber.Topic, new RenderQueue <MessageTask>(queueSize)); if (this.IsConnected) { this.webSocket.Send(ROSBridgeMsg.Subscribe(subscriber.Topic, subscriber.Type)); } return(subscriber); }
/// <summary> /// Remove a subscriber callback from this connection. /// </summary> /// <param name="subscriber"></param> public void Unsubscribe(ROSBridgeSubscriber subscriber) { if (subscriber == null) { return; } this.subscribers.Remove(subscriber); this.msgQueue.Remove(subscriber.Topic); if (this.IsConnected) { this.webSocket.Send(ROSBridgeMsg.UnSubscribe(subscriber.Topic)); } }
public MessageTask(ROSBridgeSubscriber subscriber, ROSMessage msg) { this.subscriber = subscriber; this.msg = msg; }