Skip to content

User_App_ROS_UnitySimulationExample

Mehmet Emre Çakal edited this page Oct 10, 2024 · 12 revisions

2.4 Unity Simulation Scene Example

Note: This tutorial assumes that you have completed tutorials:

ROS2 Humble - R2D2

Follow along with our tutorial video on YouTube for the complete tutorial.

Overview

This application of ROS# illustrates the communication between Unity and ROS in which the real time simulation takes place in Unity. The following figure illustrates the general schema of the application.

General Picture

The control signals are sent from ROS to Unity. Consequently, the outcomes of Unity are captured by ROS to illustrate them using rviz as an example.

  • Messages to be subscribed by Unity using ROS#:

  • /joy

  • Topics to be published by Unity using ROS#:

  • /odom

  • /joint_states

  • /camera/compressed

The movement of the mouse cursor in Ubuntu is used to control the R2D2 in Unity. Therefore, the ROS node mouse_to_joy2.py maps the movement of the mouse cursor position in the respective window to messages of the type sensor_msgs/joy. These are sent to the rosbridge_websocket to be captured by Unity.

In Unity the robot will move according to the captured movement of the mouse cursor and the topics /odom, /joint_states and /camera/compressed are published for further processing using ROS#.

Preparation

Setting up the Unity scene

  • Use Unity Simulation Scene for ROS2 importable sample from Unity Package Manager to start. Although covered in the video, please note that meshes and textures of the robot are not included in this Unity project. Instead please import them yourself as described in Transfer URDF From ROS.

Execution

  • Run the following command in your terminal:
# ROS2 Humble
ros2 launch unity_simulation_scene2 unity_simulation_scene.launch.py

This will launch rosbridge_websocket, file_server2 (see File Server Package), mouse_to_joy2.

As soon as all ROS nodes are launched, the robot in Unity is ready to move.

  • When the Play button is pressed and the mouse cursor in Ubuntu is moved the R2D2 will move in Unity.

The topics /odom, /joint_states and /camera/compressed are published by Unity using ROS# for further processing. This and the whole process of preparation and execution is demonstrated in the video mentioned above.

ROS1 Noetic - TurtleBot2

Overview

This application of ROS# illustrates the communication between Unity and ROS in which the real time simulation takes place in Unity. The following figure illustrates the general schema of the application.

General Picture

The control signals are sent from ROS to Unity. Consequently, the outcomes of Unity are captured by ROS to illustrate them using rviz as an example.

  • Messages to be subscribed by Unity using ROS#:

  • /sensor_msgs/joy

  • Topics to be published by Unity using ROS#:

  • /odom

  • /joint_states

  • /unity_image/compressed

The movement of the mouse cursor in Ubuntu is used to control the TurtleBot in Unity. Therefore, the ROS node mouse_to_joy.py maps the movement of the mouse cursor to messages of the type sensor_msgs/joy. These are sent to the rosbridge_websocket to be captured by Unity.

In Unity the robot will move according to the captured movement of the mouse cursor in Ubuntu and the topics /odom, /joint_states and /unity_image/compressed are published for further processing using ROS#.

Preparation

Setting up the Unity scene

  • Compose the Unity scene UnitySimulationScene by following this video for ROS1 Noetic.
  • You can use Unity Simulation Scene example for reference. Please note that meshes and textures of the robot are not included in this Unity project. Instead please import them yourself as described in Transfer URDF From ROS.

Execution

  • Run the following command in your terminal:
# ROS1 Noetic
roslaunch unity_simulation_scene unity_simulation_scene.launch

This will launch rosbridge_websocket, file_server (see File Server Package), mouse_to_joy and rqt_graph.

As soon as all ROS nodes are launched, the robot in Unity is ready to move.

  • When the Play button is pressed and the mouse cursor in Ubuntu is moved the TurtleBot will move in Unity.
  • After clicking the refresh button in the rqt_graph, a network similar to the following figure appears:
    rqt_graph
    Above you can see that the topic/joy is published by the ROS node mouse_to_joy and sent to Unity using rosbridge_websocket.
    playbutton

The topics /odom, /joint_states and /unity_image/compressed are published by Unity using ROS# for further processing. This and the whole process of preparation and execution is demonstrated in the video mentioned above.


© Siemens AG, 2017-2024

Clone this wiki locally