Skip to content

Commit 8c87be8

Browse files
authored
AIRO-300: Package install instructions (#79)
* AIRO-300: Ancillary package install instructions, FAQ update * Gripper rotation, ROSGeometry addition (#81)
1 parent 3e22904 commit 8c87be8

File tree

9 files changed

+108
-68
lines changed

9 files changed

+108
-68
lines changed

Diff for: README.md

+4
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ For any questions or feedback, connect directly with the Robotics team at [unity
1616

1717
| Tutorial | Description |
1818
|---|---|
19+
| [Quick Installation Instructions](tutorials/quick_setup.md) | Brief steps on installing the Unity Robotics packages |
1920
| [Pick-and-Place Demo](tutorials/pick_and_place/README.md) | A complete end-to-end demonstration, including how to set up the Unity environment, how to import a robot from URDF, and how to set up two-way communication with ROS for control |
2021
| [ROS–Unity Integration](tutorials/ros_unity_integration/README.md) | A set of component-level tutorials showing how to set up communication between ROS and Unity |
2122
| [URDF Importer](tutorials/urdf_importer/urdf_tutorial.md) | Steps on using the Unity package for loading [URDF](http://wiki.ros.org/urdf) files (Unified Robot Description Format) |
@@ -50,5 +51,8 @@ In addition to robot simulation, here are some additional, relevant Unity simula
5051
- Training a performant object detection ML model on synthetic data using Unity Perception tools [blog post](https://blogs.unity3d.com/2020/09/17/training-a-performant-object-detection-ml-model-on-synthetic-data-using-unity-perception-tools/)
5152
- Unity Perception [repository](https://github.com/Unity-Technologies/com.unity.perception)
5253

54+
## FAQs
55+
- [FAQs](faq.md)
56+
5357
## License
5458
[Apache License 2.0](LICENSE)

Diff for: faq.md

+49-2
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,23 @@
1-
# Frequently Asked Questions
1+
# Frequently Asked Questions & Troubleshooting
2+
3+
- [Frequently Asked Questions & Troubleshooting](#frequently-asked-questions--troubleshooting)
4+
- [General Questions](#general-questions)
5+
- [Is ROS 2 support planned?](#is-ros-2-support-planned)
6+
- [How does your Unity integration compare to ROS#?](#how-does-your-unity-integration-compare-to-ros)
7+
- [How can I install the Unity Packages without starting from a template project?](#how-can-i-install-the-unity-packages-without-starting-from-a-template-project)
8+
- [ROS-TCP Endpoint/Connector](#ros-tcp-endpointconnector)
9+
- [How does the TCP Endpoint compare to Rosbridge Server?](#how-does-the-tcp-endpoint-compare-to-rosbridge-server)
10+
- [I receive a `Starting server on ...` message in my ROS terminal, but see a `SocketException: A connection attempt failed because the connected party did not respond after a period of time, or established connection failed because connected host has failed to respond.` in my Unity console.](#i-receive-a-starting-server-on--message-in-my-ros-terminal-but-see-a-socketexception-a-connection-attempt-failed-because-the-connected-party-did-not-respond-after-a-period-of-time-or-established-connection-failed-because-connected-host-has-failed-to-respond-in-my-unity-console)
11+
- [I'm getting the error: `...failed because unknown error handler name 'rosmsg'`.](#im-getting-the-error-failed-because-unknown-error-handler-name-rosmsg)
12+
- [Unity can't connect to ROS!](#unity-cant-connect-to-ros)
13+
- [URDF-Importer](#urdf-importer)
14+
- [I don't see an option to Import Robot from URDF, or I have compile errors upon importing the URDF-Importer.](#i-dont-see-an-option-to-import-robot-from-urdf-or-i-have-compile-errors-upon-importing-the-urdf-importer)
15+
- [Can't find what you're looking for?](#cant-find-what-youre-looking-for)
16+
17+
# General Questions
18+
Is ROS 2 support planned?
19+
---
20+
We definitely plan to support ROS 2 in the future. Let us know more about your use case in order to prioritize our work by reaching out to us at [[email protected]](mailto:[email protected]).
221

322
How does your Unity integration compare to [ROS#](https://github.com/siemens/ros-sharp)?
423
---
@@ -8,11 +27,18 @@ In the URDF Importer we have added the functionality to instantiate a robot from
827

928
Aside from facilitating communication with the TCP Endpoint, the TCP Connector contains the `MessageGeneration` code from ROS#. We added the extra functionality that when generating a C# class from a ROS message, functions are also generated that will serialize and deserialize the messages as ROS would internally.
1029

30+
How can I install the Unity Packages without starting from a template project?
31+
---
32+
Refer to the [Quick Start](tutorials/quick_setup.md) instructions on how to import these packages.
33+
34+
35+
# ROS-TCP Endpoint/Connector
36+
1137
How does the TCP Endpoint compare to [Rosbridge Server](http://wiki.ros.org/rosbridge_server)?
1238
---
1339
To put it simply, the TCP Endpoint does not have the extra overhead of having to serialize and deserialize from JSON as its only function is to pass 'ROS serialized' messages between Unity and ROS. That being said the TCP Endpoint is not as general as ROS Bridge and has the strict requirement that all messages be serialized by the TCP Connector code.
1440

15-
Here are some prelminary numbers from a few initial tests done during the discovery stage of this project. We will publish more test results publicly after we go through more rigorous testing but these results should be generally close enough for those curious about performance improvements.
41+
Here are some preliminary numbers from a few initial tests done during the discovery stage of this project. We will publish more test results publicly after we go through more rigorous testing but these results should be generally close enough for those curious about performance improvements.
1642

1743
**Note:** These tests were run on a single machine that was only running ROS and a Unity executable.
1844

@@ -29,3 +55,24 @@ The time was logged when the message was sent from Unity before being serialized
2955

3056
- ROS# with ROS Bridge Suite took ~2 seconds
3157
- TCP Connector with TCP Endpoint took ~0.17 seconds
58+
59+
I receive a `Starting server on ...` message in my ROS terminal, but see a `SocketException: A connection attempt failed because the connected party did not respond after a period of time, or established connection failed because connected host has failed to respond.` in my Unity console.
60+
---
61+
This is likely an issue with how your network adapters are set up if you are using a virtual machine. You may need to do some troubleshooting to ensure that your guest OS can talk to your host OS and vice versa. One simple way to do this is to set up a "Host-Only" style network, but this varies based on what virtualization software you're using. Try to ensure that you can `ping` your host OS's IP from inside the guest, and can `ping` the guest from the host, then try this last step again.
62+
63+
I'm getting the error: `...failed because unknown error handler name 'rosmsg'`.
64+
---
65+
This is due to a bug in an outdated package version. Try running `sudo apt-get update && sudo apt-get upgrade` to upgrade.
66+
67+
Unity can't connect to ROS!
68+
---
69+
Ensure that the ROS IP address is entered correctly as the `Host Name` in the RosConnect component in Unity, and if you are using a `params.yaml` file, that the appropriate IP addresses are filled in.
70+
71+
# URDF-Importer
72+
73+
I don't see an option to Import Robot from URDF, or I have compile errors upon importing the URDF-Importer.
74+
---
75+
The [ArticulationBody](https://docs.unity3d.com/2020.2/Documentation/ScriptReference/ArticulationBody.html) has dependencies on Unity Editor versions [2020.2.0](https://unity3d.com/unity/whats-new/2020.2.0)+. Try updating your project to the latest 2020.2 release.
76+
77+
# Can't find what you're looking for?
78+
Connect directly with the Robotics team at [[email protected]](mailto:[email protected])!

Diff for: images/packman.png

30.1 KB
Loading

Diff for: tutorials/pick_and_place/1_urdf.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ This part includes downloading and installing the Unity Editor, setting up a bas
4141

4242
## Setting Up the Robot
4343

44-
> Note: Presumably when you opened this project, the Package Manager automatically checked out and built the URDF-Importer package for you. You can double-check this now by looking for `Packages/URDF-Importer` in the Project Browser or by opening the Package Manager window.
44+
> Note: Presumably when you opened this project, the Package Manager automatically checked out and built the URDF-Importer package for you. You can double-check this now by looking for `Packages/URDF-Importer` in the Project Browser or by opening the Package Manager window. See the [Quick Setup](../quick_setup.md) steps for adding this package to your own project.
4545

4646
1. Open the Physics Project Settings (Edit > Project Settings > Physics) and ensure the `Solver Type` is set to `Temporal Gauss Seidel`. This prevents erratic behavior in the joints that may be caused by the default solver.
4747

Diff for: tutorials/pick_and_place/2_ros_tcp.md

+8-15
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ To enable communication between Unity and ROS, a TCP endpoint running as a ROS n
4242

4343
1. If the PickAndPlaceProject Unity project is not already open, select and open it from the Unity Hub.
4444

45-
> Note: The Package Manager automatically checked out and built the ROS-TCP-Connection package in this project. You can verify this now by looking for `Packages/ROS-TCP-Connector` in the Project Browser or by opening the Package Manager window.
45+
> Note: The Package Manager automatically checked out and built the ROS-TCP-Connection package in this project. You can verify this now by looking for `Packages/ROS-TCP-Connector` in the Project Browser or by opening the Package Manager window. See the [Quick Setup](../quick_setup.md) steps for adding this package to your own project.
4646
4747
> The ROS-TCP-Connector package includes two pieces: TcpConnector, which contains the `ROSConnection` script described above, and MessageGeneration, which generates C# scripts from ROS msg and srv files.
4848
@@ -104,23 +104,16 @@ To enable communication between Unity and ROS, a TCP endpoint running as a ROS n
104104
// Pick Pose
105105
sourceDestinationMessage.pick_pose = new RosMessageTypes.Geometry.Pose
106106
{
107-
position = new Point(
108-
target.transform.position.z,
109-
-target.transform.position.x,
110-
target.transform.position.y
111-
),
112-
orientation = pickOrientation
107+
position = target.transform.position.To<FLU>(),
108+
// The hardcoded x/z angles assure that the gripper is always positioned above the target cube before grasping.
109+
orientation = Quaternion.Euler(90, target.transform.eulerAngles.y, 0).To<FLU>()
113110
};
114111

115112
// Place Pose
116113
sourceDestinationMessage.place_pose = new RosMessageTypes.Geometry.Pose
117114
{
118-
position = new Point(
119-
targetPlacement.transform.position.z,
120-
-targetPlacement.transform.position.x,
121-
targetPlacement.transform.position.y
122-
),
123-
orientation = pickOrientation
115+
position = targetPlacement.transform.position.To<FLU>(),
116+
orientation = pickOrientation.To<FLU>()
124117
};
125118

126119
// Finally send the message to server_endpoint.py running in ROS
@@ -130,7 +123,7 @@ To enable communication between Unity and ROS, a TCP endpoint running as a ROS n
130123

131124
> This function first takes in the current joint target values. Then, it grabs the poses of the `target` and the `targetPlacement` objects, adds them to the newly created message `sourceDestinationMessage`, and calls `Send()` to send this information to the ROS topic `topicName` (defined as `"SourceDestination_input"`).
132125
133-
> Note: Going from Unity world space to ROS world space requires a conversion. Unity's `(x,y,z)` is equivalent to the ROS `(z,-x,y)` coordinate.
126+
> Note: Going from Unity world space to ROS world space requires a conversion. Unity's `(x,y,z)` is equivalent to the ROS `(z,-x,y)` coordinate. These conversions are provided via the [ROSGeometry component](https://github.com/Unity-Technologies/ROS-TCP-Connector/blob/main/ROSGeometry.md) in the ROS-TCP-Connector package.
134127
135128
1. Return to the Unity Editor. Now that the message contents have been defined and the publisher script added, it needs to be added to the Unity world to run its functionality.
136129

@@ -176,7 +169,7 @@ To enable communication between Unity and ROS, a TCP endpoint running as a ROS n
176169

177170
> Note: This project has been tested with Python 2 and ROS Melodic, as well as Python 3 and ROS Noetic.
178171
179-
Most of the ROS setup has been provided via the `niryo_moveit` package. This section will describe the `.launch` files and start the necessary ROS nodes for communication. Two methods are provideds to launch ROS nodes and services: either using a ROS docker container or doing it manually in your own ROS environment.
172+
Most of the ROS setup has been provided via the `niryo_moveit` package. This section will describe the `.launch` files and start the necessary ROS nodes for communication. Two methods are provided to launch ROS nodes and services: either using a ROS docker container or doing it manually in your own ROS environment.
180173

181174
### Use Docker Container
182175

Diff for: tutorials/pick_and_place/3_pick_and_place.md

+6-17
Original file line numberDiff line numberDiff line change
@@ -37,27 +37,16 @@ Steps covered in this tutorial includes invoking a motion planning service in RO
3737
// Pick Pose
3838
request.pick_pose = new RosMessageTypes.Geometry.Pose
3939
{
40-
position = new Point(
41-
target.transform.position.z,
42-
-target.transform.position.x,
43-
// Add pick pose offset to position the gripper above target to avoid collisions
44-
target.transform.position.y + pickPoseOffset
45-
),
46-
// Orientation is hardcoded for this example so the gripper is always directly above the target object
47-
orientation = pickOrientation
40+
position = (target.transform.position + pickPoseOffset).To<FLU>(),
41+
// The hardcoded x/z angles assure that the gripper is always positioned above the target cube before grasping.
42+
orientation = Quaternion.Euler(90, target.transform.eulerAngles.y, 0).To<FLU>()
4843
};
4944

5045
// Place Pose
5146
request.place_pose = new RosMessageTypes.Geometry.Pose
5247
{
53-
position = new Point(
54-
targetPlacement.transform.position.z,
55-
-targetPlacement.transform.position.x,
56-
// Use the same pick pose offset so the target cube can be seen dropping into position
57-
targetPlacement.transform.position.y + pickPoseOffset
58-
),
59-
// Orientation is hardcoded for this example so the gripper is always directly above the target object
60-
orientation = pickOrientation
48+
position = (targetPlacement.transform.position + pickPoseOffset).To<FLU>(),
49+
orientation = pickOrientation.To<FLU>()
6150
};
6251

6352
ros.SendServiceMessage<MoverServiceResponse>(rosServiceName, request, TrajectoryResponse);
@@ -160,7 +149,7 @@ def plan_trajectory(move_group, destination_pose, start_joint_angles):
160149

161150
### Use Docker Container
162151

163-
1. If you are using ROS docker container and have not already build the ROS docker image. Follow the steps in [Part 2](2_ros_tcp.md) to build the `unity-robotics:pick-and-place` docker image.
152+
1. If you are using ROS docker container and have not already built the ROS docker image. Follow the steps in [Part 2](2_ros_tcp.md) to build the `unity-robotics:pick-and-place` docker image.
164153

165154
### Manually Setup ROS
166155

Diff for: tutorials/pick_and_place/Scripts/SourceDestinationPublisher.cs

+7-14
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,8 @@
11
using RosMessageTypes.Geometry;
22
using RosMessageTypes.NiryoMoveit;
33
using UnityEngine;
4-
using RosQuaternion = RosMessageTypes.Geometry.Quaternion;
4+
using ROSGeometry;
5+
using Quaternion = UnityEngine.Quaternion;
56

67
public class SourceDestinationPublisher : MonoBehaviour
78
{
@@ -16,7 +17,7 @@ public class SourceDestinationPublisher : MonoBehaviour
1617
public GameObject target;
1718
public GameObject targetPlacement;
1819

19-
private readonly RosQuaternion pickOrientation = new RosQuaternion(0.5,0.5,-0.5,0.5);
20+
private readonly Quaternion pickOrientation = Quaternion.Euler(90, 90, 0);
2021

2122
// Articulation Bodies
2223
private ArticulationBody[] jointArticulationBodies;
@@ -60,23 +61,15 @@ public void Publish()
6061
// Pick Pose
6162
sourceDestinationMessage.pick_pose = new RosMessageTypes.Geometry.Pose
6263
{
63-
position = new Point(
64-
target.transform.position.z,
65-
-target.transform.position.x,
66-
target.transform.position.y
67-
),
68-
orientation = pickOrientation
64+
position = target.transform.position.To<FLU>(),
65+
orientation = Quaternion.Euler(90, target.transform.eulerAngles.y, 0).To<FLU>()
6966
};
7067

7168
// Place Pose
7269
sourceDestinationMessage.place_pose = new RosMessageTypes.Geometry.Pose
7370
{
74-
position = new Point(
75-
targetPlacement.transform.position.z,
76-
-targetPlacement.transform.position.x,
77-
targetPlacement.transform.position.y
78-
),
79-
orientation = pickOrientation
71+
position = targetPlacement.transform.position.To<FLU>(),
72+
orientation = pickOrientation.To<FLU>()
8073
};
8174

8275
// Finally send the message to server_endpoint.py running in ROS

Diff for: tutorials/pick_and_place/Scripts/TrajectoryPlanner.cs

+13-19
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,13 @@
33
using RosMessageTypes.Geometry;
44
using RosMessageTypes.NiryoMoveit;
55
using UnityEngine;
6-
using RosQuaternion = RosMessageTypes.Geometry.Quaternion;
6+
7+
using ROSGeometry;
8+
using Quaternion = UnityEngine.Quaternion;
9+
using RosImage = RosMessageTypes.Sensor.Image;
710
using Transform = UnityEngine.Transform;
11+
using Vector3 = UnityEngine.Vector3;
12+
813

914
public class TrajectoryPlanner : MonoBehaviour
1015
{
@@ -15,10 +20,10 @@ public class TrajectoryPlanner : MonoBehaviour
1520
// Hardcoded variables
1621
private readonly float jointAssignmentWait = 0.1f;
1722
private readonly float poseAssignmentWait = 0.5f;
18-
private readonly float pickPoseOffset = 0.1f;
23+
private readonly Vector3 pickPoseOffset = Vector3.up * 0.1f;
1924

2025
// Assures that the gripper is always positioned above the target cube before grasping.
21-
private readonly RosQuaternion pickOrientation = new RosQuaternion(0.5,0.5,-0.5,0.5);
26+
private readonly Quaternion pickOrientation = Quaternion.Euler(90, 90, 0);
2227

2328
// Variables required for ROS communication
2429
public string rosServiceName = "niryo_moveit";
@@ -107,27 +112,16 @@ public void PublishJoints()
107112
// Pick Pose
108113
request.pick_pose = new RosMessageTypes.Geometry.Pose
109114
{
110-
position = new Point(
111-
target.transform.position.z,
112-
-target.transform.position.x,
113-
// Add pick pose offset to position the gripper above target to avoid collisions
114-
target.transform.position.y + pickPoseOffset
115-
),
116-
// Orientation is hardcoded for this example so the gripper is always directly above the target object
117-
orientation = pickOrientation
115+
position = (target.transform.position + pickPoseOffset).To<FLU>(),
116+
// The hardcoded x/z angles assure that the gripper is always positioned above the target cube before grasping.
117+
orientation = Quaternion.Euler(90, target.transform.eulerAngles.y, 0).To<FLU>()
118118
};
119119

120120
// Place Pose
121121
request.place_pose = new RosMessageTypes.Geometry.Pose
122122
{
123-
position = new Point(
124-
targetPlacement.transform.position.z,
125-
-targetPlacement.transform.position.x,
126-
// Use the same pick pose offset so the target cube can be seen dropping into position
127-
targetPlacement.transform.position.y + pickPoseOffset
128-
),
129-
// Orientation is hardcoded for this example so the gripper is always directly above the target object
130-
orientation = pickOrientation
123+
position = (targetPlacement.transform.position + pickPoseOffset).To<FLU>(),
124+
orientation = pickOrientation.To<FLU>()
131125
};
132126

133127
ros.SendServiceMessage<MoverServiceResponse>(rosServiceName, request, TrajectoryResponse);

0 commit comments

Comments
 (0)