Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
using RosSharp;
using RosSharp.Control;
using RosSharp.Urdf.Editor;
using Unity.EditorCoroutines.Editor;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shouldn't need this import.

Copy link
Contributor Author

@peifeng-unity peifeng-unity Feb 22, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry that I didn't notice. Created a new PR to follow up #163

using UnityEditor;
using UnityEngine;
using Unity.Robotics.ROSTCPConnector;
Expand Down Expand Up @@ -75,8 +76,10 @@ void Awake()
{
EditorApplication.LockReloadAssemblies();
SetupScene();
SetupRos();
CreateTrajectoryPlannerPubliser();
AddRosMessages();
ImportRobot();
CreateRosConnection();
CreateTrajectoryPlannerPublisher();
}

void Update()
Expand Down Expand Up @@ -104,31 +107,18 @@ void OnApplicationQuit()
private void SetupScene()
{
// Instantiate the table, target, and target placement
GameObject table = InstantiatePrefab(tableName);
GameObject target = InstantiatePrefab(targetName);
GameObject targetPlacement = InstantiatePrefab(targetPlacementName);
InstantiatePrefab(tableName);
InstantiatePrefab(targetName);
InstantiatePrefab(targetPlacementName);

// Adjust main camera
GameObject camera = GameObject.Find(cameraName);
camera.transform.position = cameraPosition;
camera.transform.rotation = cameraRotation;

// Import Niryo One with URDF importer
string urdfFilepath = Path.Combine(Application.dataPath, urdfRelativeFilepath);
ImportRobot(urdfFilepath, ImportSettings.convexDecomposer.unity);

// Adjust robot parameters
Controller controller = GameObject.Find(niryoOneName).GetComponent<Controller>();
controller.stiffness = controllerStiffness;
controller.damping = controllerDamping;
controller.forceLimit = controllerForceLimit;
controller.speed = controllerSpeed;
controller.acceleration = controllerAcceleration;
GameObject.Find(baseLinkName).GetComponent<ArticulationBody>().immovable = true;
}

// Tutorial Part 2 without the Publisher object
private void SetupRos()
private void AddRosMessages()
{
if (generateRosMessages)
{
Expand All @@ -152,19 +142,9 @@ private void SetupRos()
scripts.AddRange(Directory.GetFiles(rosMessagesDirectory, scriptPattern, SearchOption.AllDirectories));
scripts.AddRange(Directory.GetFiles(externalScriptsDirectory));
RecompileScripts(scripts.ToArray());

// Create RosConnect
GameObject rosConnect = new GameObject(rosConnectName);
rosConnection = rosConnect.AddComponent<ROSConnection>();
rosConnection.rosIPAddress = hostIP;
rosConnection.rosPort = hostPort;
rosConnection.overrideUnityIP = overrideUnityIP;
rosConnection.unityPort = unityPort;
rosConnection.awaitDataMaxRetries = awaitDataMaxRetries;
rosConnection.awaitDataSleepSeconds = awaitDataSleepSeconds;
}

private void CreateTrajectoryPlannerPubliser()
private void CreateTrajectoryPlannerPublisher()
{
GameObject publisher = new GameObject(publisherName);
dynamic planner = publisher.AddComponent(assembly.GetType(trajectoryPlannerType));
Expand All @@ -182,15 +162,39 @@ private GameObject InstantiatePrefab(string name)
return gameObject;
}

private void ImportRobot(string urdfFilepath, ImportSettings.convexDecomposer convexDecomposer)
private void CreateRosConnection()
{
// Import Niryo One by URDF Importer
ImportSettings settings = new ImportSettings
// Create RosConnect
GameObject rosConnect = new GameObject(rosConnectName);
rosConnection = rosConnect.AddComponent<ROSConnection>();
rosConnection.rosIPAddress = hostIP;
rosConnection.rosPort = hostPort;
rosConnection.overrideUnityIP = overrideUnityIP;
rosConnection.unityPort = unityPort;
rosConnection.awaitDataMaxRetries = awaitDataMaxRetries;
rosConnection.awaitDataSleepSeconds = awaitDataSleepSeconds;
}

private void ImportRobot()
{
ImportSettings urdfImportSettings = new ImportSettings
{
choosenAxis = ImportSettings.axisType.yAxis,
convexMethod = convexDecomposer,
convexMethod = ImportSettings.convexDecomposer.unity
};
UrdfRobotExtensions.Create(urdfFilepath, settings);
// Import Niryo One with URDF importer
string urdfFilepath = Path.Combine(Application.dataPath, urdfRelativeFilepath);
// Create is a coroutine that would usually run only in EditMode, so we need to force its execution here
var robotImporter = UrdfRobotExtensions.Create(urdfFilepath, urdfImportSettings, false);
while (robotImporter.MoveNext()) {}
// Adjust robot parameters
Controller controller = GameObject.Find(niryoOneName).GetComponent<Controller>();
controller.stiffness = controllerStiffness;
controller.damping = controllerDamping;
controller.forceLimit = controllerForceLimit;
controller.speed = controllerSpeed;
controller.acceleration = controllerAcceleration;
GameObject.Find(baseLinkName).GetComponent<ArticulationBody>().immovable = true;
}

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