private void OnGUI()
        {
            GUILayout.Label("URDF Asset Importer", EditorStyles.boldLabel);
            EditorGUILayout.BeginHorizontal();
            EditorGUIUtility.labelWidth = 100;
            protocolType = (RosConnector.Protocols)EditorGUILayout.EnumPopup("Protocol", protocolType);
            EditorGUILayout.EndHorizontal();

            EditorGUILayout.BeginHorizontal();
            address = EditorGUILayout.TextField("Address", address);
            EditorGUILayout.EndHorizontal();

            EditorGUILayout.BeginHorizontal();
            timeout = EditorGUILayout.IntField("Timeout [s]", timeout);
            EditorGUILayout.EndHorizontal();

            EditorGUILayout.BeginHorizontal();
            assetPath = EditorGUILayout.TextField("Asset Path", assetPath);
            EditorGUILayout.EndHorizontal();

            EditorGUILayout.BeginHorizontal();
            EditorGUIUtility.labelWidth = 200;
            robotDescriptionParamName   = EditorGUILayout.TextField("Robot Description Param Name", robotDescriptionParamName);
            EditorGUILayout.EndHorizontal();
            EditorGUILayout.BeginHorizontal();
            EditorGUILayout.Space();
            if (GUILayout.Button("Reset to Default", GUILayout.Width(150)))
            {
                DeleteEditorPrefs();
                GetEditorPrefs();
            }
            EditorGUILayout.EndHorizontal();

            GUILayout.Space(20);
            EditorGUILayout.BeginHorizontal();

            if (GUILayout.Button("Read Robot Description."))
            {
                SetEditorPrefs();

                Thread rosSocketConnectThread = new Thread(() => importHandler.BeginRosImport(protocolType, address, timeout, assetPath, robotDescriptionParamName));
                rosSocketConnectThread.Start();
            }
            EditorGUILayout.EndHorizontal();

            GUILayout.Space(20);

            EditorGUIUtility.labelWidth = 300;

            DrawLabelField("1. rosbridge_server Connected:", "connected");
            DrawLabelField("2. Robot Name Received:", "robotNameReceived");
            DrawLabelField("3. Robot Description Received:", "robotDescriptionReceived");
            DrawLabelField("4. Resource Files Received:", "resourceFilesReceived");
            DrawLabelField("5. rosbridge_server Disconnected:", "disconnected");
            DrawLabelField("6. Import Complete:", "importComplete");
        }
Example #2
0
        public void Transfer(RosConnector.Protocols protocolType, string serverUrl, int timeout, string urdfPath, string rosPackage)
        {
            if (Path.GetExtension(urdfPath)?.ToLowerInvariant() != ".urdf")
            {
                Debug.LogWarning("Please select a valid URDF file to publish.");
                return;
            }

            Thread transferToRos = new Thread(() => TransferAsync(protocolType, serverUrl, timeout, urdfPath, rosPackage));

            transferToRos.Start();
        }
Example #3
0
        private void GetEditorPrefs()
        {
            protocolType = (RosConnector.Protocols)(EditorPrefs.HasKey("UrdfImporterProtocolNumber") ?
                                                    EditorPrefs.GetInt("UrdfImporterProtocolNumber") : 1);

            address = (EditorPrefs.HasKey("UrdfImporterAddress") ?
                       EditorPrefs.GetString("UrdfImporterAddress") :
                       "ws://192.168.0.1:9090");

            assetPath = (EditorPrefs.HasKey("UrdfImporterAssetPath") ?
                         EditorPrefs.GetString("UrdfImporterAssetPath") :
                         Path.Combine(Path.Combine(Path.GetFullPath("."), "Assets"), "Urdf"));

            timeout = (EditorPrefs.HasKey("UrdfImporterTimeout") ?
                       EditorPrefs.GetInt("UrdfImporterTimeout") :
                       10);
        }
        public void BeginRosImport(RosConnector.Protocols protocolType, string serverUrl, int timeout, string assetPath)
        {
            this.timeout   = timeout;
            this.assetPath = assetPath;

            // initialize
            ResetStatusEvents();

            rosSocket = RosConnector.ConnectToRos(protocolType, serverUrl, OnConnected, OnClosed);

            if (!StatusEvents["connected"].WaitOne(timeout * 1000))
            {
                Debug.LogWarning("Failed to connect to ROS before timeout");
                return;
            }

            ImportAssets();
        }
Example #5
0
        private void TransferAsync(RosConnector.Protocols protocolType, string serverUrl, int timeout, string urdfPath, string rosPackage)
        {
            RosSocket = RosConnector.ConnectToRos(protocolType, serverUrl, OnConnected, OnClose);

            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();
        }
Example #6
0
        private void GetEditorPrefs()
        {
            protocolType = (RosConnector.Protocols)(EditorPrefs.HasKey("UrdfPublisherProtocolNumber") ?
                                                    EditorPrefs.GetInt("UrdfPublisherProtocolNumber") : 1);

            serverUrl = (EditorPrefs.HasKey("UrdfPublisherServerUrl") ?
                         EditorPrefs.GetString("UrdfPublisherServerUrl") :
                         "ws://192.168.0.1:9090");

            urdfPath = (EditorPrefs.HasKey("UrdfPublisherUrdfPath") ?
                        EditorPrefs.GetString("UrdfPublisherUrdfPath") :
                        Path.Combine(Path.Combine(Path.GetFullPath("."), "Assets"), "Urdf"));

            rosPackage = (EditorPrefs.HasKey("UrdfPublisherRosPackage") ?
                          EditorPrefs.GetString("UrdfPublisherRosPackage") :
                          "new_package");

            timeout = (EditorPrefs.HasKey("UrdfPublisherTimeout") ?
                       EditorPrefs.GetInt("UrdfPublisherTimeout") :
                       10);
        }
Example #7
0
        private void OnGUI()
        {
            GUILayout.Label("URDF Transfer (From ROS to Unity)", EditorStyles.boldLabel);

            EditorGUILayout.BeginHorizontal();
            address = EditorGUILayout.TextField("Address", address);
            EditorGUILayout.EndHorizontal();

            showSettings = EditorGUILayout.Foldout(showSettings, "Settings");
            if (showSettings)
            {
                EditorGUILayout.BeginHorizontal();
                EditorGUIUtility.labelWidth = 100;
                protocolType = (RosConnector.Protocols)EditorGUILayout.EnumPopup("Protocol", protocolType);
                EditorGUILayout.EndHorizontal();

                //TODO URDF Parameter
                EditorGUILayout.BeginHorizontal();
                urdfParameter = EditorGUILayout.TextField("URDF Parameter", urdfParameter);
                EditorGUILayout.EndHorizontal();

                EditorGUILayout.BeginHorizontal();
                timeout = EditorGUILayout.IntField("Timeout [s]", timeout);
                EditorGUILayout.EndHorizontal();

                EditorGUILayout.BeginHorizontal();
                assetPath = EditorGUILayout.TextField("Asset Path", assetPath);
                EditorGUILayout.EndHorizontal();
            }

            EditorGUILayout.BeginHorizontal();
            EditorGUILayout.Space();
            if (GUILayout.Button("Reset to Default", GUILayout.Width(150)))
            {
                DeleteEditorPrefs();
                GetEditorPrefs();
            }
            EditorGUILayout.EndHorizontal();

            GUILayout.Space(20);
            EditorGUILayout.BeginHorizontal();

            if (GUILayout.Button("Read Robot Description"))
            {
                SetEditorPrefs();

                Thread rosSocketConnectThread = new Thread(() => transferHandler.TransferUrdf(protocolType, address, timeout, assetPath, urdfParameter));
                rosSocketConnectThread.Start();
            }
            EditorGUILayout.EndHorizontal();

            GUILayout.Space(20);

            EditorGUIUtility.labelWidth = 300;

            DrawLabelField("Connected:", "connected");
            DrawLabelField("Robot Name Received:", "robotNameReceived");
            DrawLabelField("Robot Description Received:", "robotDescriptionReceived");
            DrawLabelField("Resource Files Received:", "resourceFilesReceived");
            DrawLabelField("Disconnected:", "disconnected");
            DrawLabelField("Import Complete:", "importComplete");
        }
Example #8
0
        private void OnGUI()
        {
            GUILayout.Label("URDF Transfer (From Unity to ROS)", EditorStyles.boldLabel);

            EditorGUILayout.BeginHorizontal();
            EditorGUIUtility.labelWidth = 100;
            protocolType = (RosConnector.Protocols)EditorGUILayout.EnumPopup("Protocol", protocolType);
            EditorGUILayout.EndHorizontal();

            EditorGUILayout.BeginHorizontal();
            serverUrl = EditorGUILayout.TextField("Server URL", serverUrl);
            EditorGUILayout.EndHorizontal();

            EditorGUILayout.BeginHorizontal();
            timeout = EditorGUILayout.IntField("Timeout [s]", timeout);
            EditorGUILayout.EndHorizontal();

            EditorGUILayout.BeginHorizontal();
            urdfPath = EditorGUILayout.TextField("URDF to export", urdfPath);
            if (GUILayout.Button("Select", new GUIStyle(EditorStyles.miniButtonRight)
            {
                fixedWidth = 75
            }))
            {
                urdfPath = EditorUtility.OpenFilePanel("Select a URDF file", urdfPath, "urdf");
            }
            EditorGUILayout.EndHorizontal();

            EditorGUILayout.BeginHorizontal();
            rosPackage = EditorGUILayout.TextField(
                new GUIContent("ROS package",
                               "The package where all meshes and resources files will be exported to in ROS."),
                rosPackage);
            EditorGUILayout.EndHorizontal();

            EditorGUILayout.BeginHorizontal();
            EditorGUILayout.Space();
            if (GUILayout.Button("Reset to Default", GUILayout.Width(150)))
            {
                DeleteEditorPrefs();
                GetEditorPrefs();
            }
            EditorGUILayout.EndHorizontal();

            GUILayout.Space(10);
            EditorGUILayout.BeginHorizontal();

            if (GUILayout.Button("Publish Robot Description"))
            {
                SetEditorPrefs();
                transferHandler.Transfer(protocolType, serverUrl, timeout, urdfPath, rosPackage);
            }
            EditorGUILayout.EndHorizontal();


            GUILayout.Space(20);
            EditorGUIUtility.labelWidth = 225;

            DrawLabelField("Connected: ", "connected");
            DrawLabelField("Robot name published: ", "robotNamePublished");
            DrawLabelField("Robot description published: ", "robotDescriptionPublished");
            DrawLabelField("All resources files published: ", "resourceFilesSent");

            GUILayout.Space(10);
            EditorGUI.BeginDisabledGroup(transferHandler.RosSocket == null || !transferHandler.RosSocket.protocol.IsAlive());
            if (GUILayout.Button("Close Connection"))
            {
                transferHandler.RosSocket?.Close();
            }

            EditorGUI.EndDisabledGroup();
        }