public static RosSocket ConnectToRos(RosBridgeClient.Protocols.Protocol protocolType, string serverUrl, EventHandler onConnected = null, EventHandler onClosed = null, RosSocket.SerializerEnum serializer = RosSocket.SerializerEnum.JSON) { RosBridgeClient.Protocols.IProtocol protocol = RosBridgeClient.Protocols.ProtocolInitializer.GetProtocol(protocolType, serverUrl); protocol.OnConnected += onConnected; protocol.OnClosed += onClosed; return(new RosSocket(protocol, serializer)); }
public static RosSocket ConnectToRos(Protocols protocolType, string serverUrl, EventHandler onConnected = null, EventHandler onClosed = null) { RosBridgeClient.Protocols.IProtocol protocol = GetProtocol(protocolType, serverUrl); protocol.OnConnected += onConnected; protocol.OnClosed += onClosed; return(new RosSocket(protocol)); }
public static RosSocket ConnectToRos(Protocols protocolType, string serverUrl, EventHandler onConnected = null, EventHandler onClosed = null, RosSocket.SerializerEnum serializer = RosSocket.SerializerEnum.JSON) { RosBridgeClient.Protocols.IProtocol protocol = GetProtocol(protocolType, serverUrl); protocol.OnConnected += onConnected; protocol.OnClosed += onClosed; Debug.Log("protocolType: " + protocolType + " serverUrl:" + serverUrl); return(new RosSocket(protocol, serializer)); }
public void Awake() { RosBridgeClient.Protocols.IProtocol protocol = GetProtocol(); protocol.OnConnected += OnConnected; protocol.OnClosed += OnClosed; RosSocket = new RosSocket(protocol); if (!IsConnected.WaitOne(timeout * 1000)) { Debug.LogWarning("Failed to connect to RosBridge at: " + RosBridgeServerUrl); } }
private void rosSocketConnect() { // initialize foreach (ManualResetEvent manualResetEvent in status.Values) { manualResetEvent.Reset(); } // connect to rosbrige_suite: RosBridgeClient.Protocols.IProtocol protocol = GetProtocol(); RosSocket rosSocket = new RosSocket(protocol); CheckConnection(protocol); if (!status["connected"].WaitOne(0)) { rosSocket.Close(); return; } // setup urdfImporter RosBridgeClient.UrdfImporter urdfImporter = new RosBridgeClient.UrdfImporter(rosSocket, assetPath); status["robotNameReceived"] = urdfImporter.Status["robotNameReceived"]; status["robotDescriptionReceived"] = urdfImporter.Status["robotDescriptionReceived"]; status["resourceFilesReceived"] = urdfImporter.Status["resourceFilesReceived"]; urdfImporter.Import(); if (status["robotNameReceived"].WaitOne(timeout * 1000)) { robotName = urdfImporter.RobotName; localDirectory = urdfImporter.LocalDirectory; } // import URDF assets: if (status["resourceFilesReceived"].WaitOne(timeout * 1000)) { Debug.Log("Imported urdf resources to " + urdfImporter.LocalDirectory); } else { Debug.LogWarning("Not all resource files have been received before timeout."); } status["disconnected"].Set(); rosSocket.Close(); }
public void BeginRosImport(int protocolNumber, string address, int timeout, string assetPath) { this.protocolNumber = protocolNumber; this.address = address; this.timeout = timeout; this.assetPath = assetPath; // initialize ResetStatusEvents(); RosBridgeClient.Protocols.IProtocol protocol = GetProtocol(); protocol.OnConnected += OnConnected; protocol.OnClosed += OnClose; rosSocket = new RosSocket(protocol); ImportAssets(); }
private void CheckConnection(RosBridgeClient.Protocols.IProtocol protocol) { Debug.Log("Attempting to connect to ROS"); System.Diagnostics.Stopwatch stopwatch = new System.Diagnostics.Stopwatch(); stopwatch.Start(); while (!protocol.IsAlive() && stopwatch.Elapsed < TimeSpan.FromSeconds(timeout)) { Thread.Sleep(500); } stopwatch.Stop(); if (protocol.IsAlive()) { status["connected"].Set(); } else { Debug.LogWarning("Failed to connect to ROS before timeout"); } }