// on ROS system: // launch before starting: // roslaunch file_server ros_sharp_communication.launch // launch after starting: // roslaunch file_server visualize_robot.launch public static void Main(string[] args) { string uri = "ws://192.168.56.102:9090"; string robotDescription = Path.Combine(Directory.GetCurrentDirectory(), "..", "..", "TestUrdf", "R2D2WithTexture.urdf"); WebSocketNetProtocol webSocketNetProtocol = new WebSocketNetProtocol(uri); RosSocket rosSocket = new RosSocket(webSocketNetProtocol); // Publication: UrdfTransferToRos transferor = new UrdfTransferToRos(rosSocket, "Robot", robotDescription, "test_package"); transferor.Transfer(); transferor.Status["robotNamePublished"].WaitOne(); Console.WriteLine("Robot Name Published: " + transferor.RobotName); transferor.Status["robotDescriptionPublished"].WaitOne(); Console.WriteLine("Robot Description received... "); transferor.Status["resourceFilesSent"].WaitOne(); Console.WriteLine("Resource Files sent: " + transferor.FilesBeingProcessed.Count); Console.WriteLine("Press any key to close..."); Console.ReadKey(true); rosSocket.Close(); }
private void TransferAsync(Protocols.Protocol protocolType, string serverUrl, int timeout, string urdfPath, string rosPackage, RosSocket.SerializerEnum serializer) { RosSocket = RosConnector.ConnectToRos(protocolType, serverUrl, OnConnected, OnClose, serializer); if (!StatusEvents["connected"].WaitOne(timeout * 1000)) { Debug.LogWarning("Failed to connect to " + serverUrl + " before timeout."); RosSocket.Close(); return; } string robotName = Path.GetFileName(urdfPath); UrdfTransferToRos urdfTransferToRos = new UrdfTransferToRos(RosSocket, robotName, urdfPath, rosPackage); StatusEvents["robotNamePublished"] = urdfTransferToRos.Status["robotNamePublished"]; StatusEvents["robotDescriptionPublished"] = urdfTransferToRos.Status["robotDescriptionPublished"]; StatusEvents["resourceFilesSent"] = urdfTransferToRos.Status["resourceFilesSent"]; urdfTransferToRos.Transfer(); }