A2.3 - 3D Simulation Integration
In order to bring our simulation to a 3D rendering tool compatible with XR technologies, Unity 3D is an option. Unity 3D is a versatile game engine that facilitates compatibility with more than 25 platforms, including augmented reality (AR), virtual reality (VR) and mobile devices. This engine allows the use of C# scripting, thus enabling communication with external software. In addition, it has its own in-house robotics package called Unity Robotics Hub, which offers a high-level library for communicating with ROS as well as a URDF Importer.
Importing a robot from a URDF file in Unity 3D
Using the URDF importer enables the reconstruction of the robot in Unity, represented by its visual meshes, collisions, and physical properties.
Visual meshes serve as a representation of the robot’s physical structure. Collisions come into play for calculating interactions between the Link’s rigid bodies. Physical properties, including inertia, contact coefficients, and joint dynamics, are indispensable for a precise physical simulation.
The importer reads the URDF file and deposits the data into C# classes that depict the joints and links of the robot. This data then serves as the basis for recreating a GameObjects hierarchy. Each GameObject in this hierarchy possesses an ArticulationBody component that represents a specific link. The properties derived from the URDF are assigned to the corresponding fields in the ArticulationBody.
The image below displays the robot Franka Emika imported into Unity from a URDF package.
Once the robot has been imported, a script named “controller” is available that enables control of the robot through forward kinematics via the keyboard.
Comunication between Unity 3D and ROS
To establish a comunication between Unity 3D it is necessary to set up the following packages
On the Unity side:
- URDF Importer: Unity package for handle URDF files
- ROS TCP Connector: Unity package for sending, receiving, and visualizing messages from ROS
On the ROS side:
- ROS TCP Endpoint: ROS node for sending/receiving messages from Unity
The communication process between Unity and ROS follows the same structure as ROS nodes, encompassing Publishers/Subscribers, Services/Clients, and Topics/Messages. On the ROS end, the ros_tcp_endpoint script functions as the communication node with Unity. The ROSConnection script operates on the Unity end with the ROS IP set. After the communication link has been established, any C# script can interact with the ROS nodes.
In this context, it’s essential to develop a Unity script that subscribes to the /joint_states topic, which carries a message of the sensor_msgs/JointState.msg type. This message contains data detailing the state of a set of torque-controlled joints. The state of each joint, whether revolute or prismatic, is defined by:
- The joint’s position (rad or m),
- The joint’s velocity (rad/s or m/s) and
- The effort applied to the joint (Nm or N).
Upon receiving this information, it gets integrated into the Unity model, generating a Digital Shadow that mirrors the robot’s movements in ROS. It’s crucial to note that this process remains the same when data is extracted from the actual robot.
Presented here is a script enabling subscription to the /joint_states topic and setting the positions of the joints within the Unity robot’s joints.
Unity ROSJointStateSubscriber script
using System.Collections;
using UnityEngine;
using Unity.Robotics.ROSTCPConnector;
using SensorUnity = RosMessageTypes.Sensor.JointStateMsg;
public class ROSJointStateSubscriber : MonoBehaviour
{
[SerializeField] private string rosTopic = "joint_states";
[SerializeField] private ROSConnection ROS;
[SerializeField] private ArticulationBody[] robotJoints = new ArticulationBody[9];
void Start()
{
SubscribeToTopic(rosTopic);
}
private void SubscribeToTopic(string rosTopic)
{
ROS = ROSConnection.GetOrCreateInstance();
ROS.Subscribe<SensorUnity>(rosTopic, GetJointPositions);
}
private void GetJointPositions(SensorUnity sensorMsg)
{
StartCoroutine(SetJointValues(sensorMsg));
}
IEnumerator SetJointValues(SensorUnity message)
{
for (int i = 0; i < message.name.Length; i++)
{
var joint1XDrive = robotJoints[i].xDrive;
joint1XDrive.target = (float)(message.position[i]) * Mathf.Rad2Deg;
robotJoints[i].xDrive = joint1XDrive;
}
yield return new WaitForSeconds(0.5f);
}
public void UnSubscribeToTopic(string rosTopic)
{
ROS.Unsubscribe(rosTopic);
}
Simulation running in ROS side and displayed in Unity 3D Side
Unity 3D | ROS |
Input
Unity Robotics package in order to create a two way bridge between Unity - ROS and RDF robot package in order to have an accurate representation of the robot inside Unity.
Output
- 3D rendering of the robot in Unity, represented by visual meshes, collisions, and physical properties.
- Real-time robot simulation in Unity 3D mirroring the robot’s movements in ROS (Digital Shadow).
Control
Latency of communication and packet delivery between Unity - ROS. Accuracy of the shadow twin considering the behavior of the physical twin
Resources
- Unity 3D and Unity Robotics Hub package.
- ROS TCP Connector: Unity package for sending, receiving, and visualizing messages from ROS.
- ROS TCP Endpoint: ROS node for sending/receiving messages from Unity.