Skip to content

Commit d47586f

Browse files
Fixing issue with Demo.cs not working with new URDF Importer co-routine (#162)
Co-authored-by: Devin Miller <devin.miller@unity3d.com>
1 parent ac3c5b9 commit d47586f

File tree

1 file changed

+39
-35
lines changed
  • tutorials/pick_and_place/PickAndPlaceProject/Assets/DemoScripts

1 file changed

+39
-35
lines changed

tutorials/pick_and_place/PickAndPlaceProject/Assets/DemoScripts/Demo.cs

Lines changed: 39 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
using RosSharp;
1010
using RosSharp.Control;
1111
using RosSharp.Urdf.Editor;
12+
using Unity.EditorCoroutines.Editor;
1213
using UnityEditor;
1314
using UnityEngine;
1415
using Unity.Robotics.ROSTCPConnector;
@@ -75,8 +76,10 @@ void Awake()
7576
{
7677
EditorApplication.LockReloadAssemblies();
7778
SetupScene();
78-
SetupRos();
79-
CreateTrajectoryPlannerPubliser();
79+
AddRosMessages();
80+
ImportRobot();
81+
CreateRosConnection();
82+
CreateTrajectoryPlannerPublisher();
8083
}
8184

8285
void Update()
@@ -104,31 +107,18 @@ void OnApplicationQuit()
104107
private void SetupScene()
105108
{
106109
// Instantiate the table, target, and target placement
107-
GameObject table = InstantiatePrefab(tableName);
108-
GameObject target = InstantiatePrefab(targetName);
109-
GameObject targetPlacement = InstantiatePrefab(targetPlacementName);
110+
InstantiatePrefab(tableName);
111+
InstantiatePrefab(targetName);
112+
InstantiatePrefab(targetPlacementName);
110113

111114
// Adjust main camera
112115
GameObject camera = GameObject.Find(cameraName);
113116
camera.transform.position = cameraPosition;
114117
camera.transform.rotation = cameraRotation;
115-
116-
// Import Niryo One with URDF importer
117-
string urdfFilepath = Path.Combine(Application.dataPath, urdfRelativeFilepath);
118-
ImportRobot(urdfFilepath, ImportSettings.convexDecomposer.unity);
119-
120-
// Adjust robot parameters
121-
Controller controller = GameObject.Find(niryoOneName).GetComponent<Controller>();
122-
controller.stiffness = controllerStiffness;
123-
controller.damping = controllerDamping;
124-
controller.forceLimit = controllerForceLimit;
125-
controller.speed = controllerSpeed;
126-
controller.acceleration = controllerAcceleration;
127-
GameObject.Find(baseLinkName).GetComponent<ArticulationBody>().immovable = true;
128118
}
129119

130120
// Tutorial Part 2 without the Publisher object
131-
private void SetupRos()
121+
private void AddRosMessages()
132122
{
133123
if (generateRosMessages)
134124
{
@@ -152,19 +142,9 @@ private void SetupRos()
152142
scripts.AddRange(Directory.GetFiles(rosMessagesDirectory, scriptPattern, SearchOption.AllDirectories));
153143
scripts.AddRange(Directory.GetFiles(externalScriptsDirectory));
154144
RecompileScripts(scripts.ToArray());
155-
156-
// Create RosConnect
157-
GameObject rosConnect = new GameObject(rosConnectName);
158-
rosConnection = rosConnect.AddComponent<ROSConnection>();
159-
rosConnection.rosIPAddress = hostIP;
160-
rosConnection.rosPort = hostPort;
161-
rosConnection.overrideUnityIP = overrideUnityIP;
162-
rosConnection.unityPort = unityPort;
163-
rosConnection.awaitDataMaxRetries = awaitDataMaxRetries;
164-
rosConnection.awaitDataSleepSeconds = awaitDataSleepSeconds;
165145
}
166146

167-
private void CreateTrajectoryPlannerPubliser()
147+
private void CreateTrajectoryPlannerPublisher()
168148
{
169149
GameObject publisher = new GameObject(publisherName);
170150
dynamic planner = publisher.AddComponent(assembly.GetType(trajectoryPlannerType));
@@ -182,15 +162,39 @@ private GameObject InstantiatePrefab(string name)
182162
return gameObject;
183163
}
184164

185-
private void ImportRobot(string urdfFilepath, ImportSettings.convexDecomposer convexDecomposer)
165+
private void CreateRosConnection()
186166
{
187-
// Import Niryo One by URDF Importer
188-
ImportSettings settings = new ImportSettings
167+
// Create RosConnect
168+
GameObject rosConnect = new GameObject(rosConnectName);
169+
rosConnection = rosConnect.AddComponent<ROSConnection>();
170+
rosConnection.rosIPAddress = hostIP;
171+
rosConnection.rosPort = hostPort;
172+
rosConnection.overrideUnityIP = overrideUnityIP;
173+
rosConnection.unityPort = unityPort;
174+
rosConnection.awaitDataMaxRetries = awaitDataMaxRetries;
175+
rosConnection.awaitDataSleepSeconds = awaitDataSleepSeconds;
176+
}
177+
178+
private void ImportRobot()
179+
{
180+
ImportSettings urdfImportSettings = new ImportSettings
189181
{
190182
choosenAxis = ImportSettings.axisType.yAxis,
191-
convexMethod = convexDecomposer,
183+
convexMethod = ImportSettings.convexDecomposer.unity
192184
};
193-
UrdfRobotExtensions.Create(urdfFilepath, settings);
185+
// Import Niryo One with URDF importer
186+
string urdfFilepath = Path.Combine(Application.dataPath, urdfRelativeFilepath);
187+
// Create is a coroutine that would usually run only in EditMode, so we need to force its execution here
188+
var robotImporter = UrdfRobotExtensions.Create(urdfFilepath, urdfImportSettings, false);
189+
while (robotImporter.MoveNext()) {}
190+
// Adjust robot parameters
191+
Controller controller = GameObject.Find(niryoOneName).GetComponent<Controller>();
192+
controller.stiffness = controllerStiffness;
193+
controller.damping = controllerDamping;
194+
controller.forceLimit = controllerForceLimit;
195+
controller.speed = controllerSpeed;
196+
controller.acceleration = controllerAcceleration;
197+
GameObject.Find(baseLinkName).GetComponent<ArticulationBody>().immovable = true;
194198
}
195199

196200
// Credit to https://www.codeproject.com/Tips/715891/Compiling-Csharp-Code-at-Runtime

0 commit comments

Comments
 (0)