-
Notifications
You must be signed in to change notification settings - Fork 371
User_App_QuickStart
This tutorial assumes that you have completed:
- Create an empty GameObject in your Unity scene (
Ctrl+Shift+N
). - Add the
Ros Connector
script to the GameObject (Ctrl+Shift+A
). - Fill in your local address and select your desired serializer and protocol. A specific serializer/protocol might not work for your other packages. If both serializers/protocols are not working for your needs, head to serializers and protocols wiki pages for more information. If Unity doesn't complain, leave it as is.
- Run your (rosbridge server and) Unity project. If you see a 'connected' notification, you've successfully configured/connected the ROS#.
ROS# comes with various of prewritten message types, subscriber and publisher classes. For the sake of simplicty, let's use the StringSubscriber.cs
for this tutorial. Before moving on, let's examine the code first.
com.siemens.ros-sharp\Runtime\RosBridgeClient\RosCommunication\StringSubscriber.cs
:
namespace RosSharp.RosBridgeClient
{
public class StringSubscriber : UnitySubscriber<MessageTypes.Std.String>
{
public bool isMessageReceived;
private string messageData;
protected override void Start()
{
base.Start();
}
...
- We see that the
StringSubsriber
class implements theUnitySubsriber
abstract MonoBehaviour template class, just like any other subsriber class in ROS#. As the name suggests, theStringSubsriber
class implements the template with the<MessageTypes.Std.String>
message type. Message types are located in theRosSharp.RosBridgeClient.MessageTypes
namespace. ROS# ships with a bundle of popular message types, but you can create a completely custom message type for your needs if you wish. See adding new message types for more information.
...
protected override void ReceiveMessage(MessageTypes.Std.String message)
{
messageData = message.data;
isMessageReceived = true;
}
...
-
ReceiveMessage
is an implemented abstract callback method that is triggered in every incoming message. In this example, it just updates themessageData
.
...
void FixedUpdate()
{
Debug.Log("Received message: " + messageData);
}
}
}
- Finally, we can use Unity's built-in
FixedUpdate
method to print themessageData
at a fixed interval. This debugging rate is not relevant to the subscription rate, as it's basically controlled by the publisher and, most importantly, by theTimeStep
variable in the baseUnitySubsriber
class.
-
Open your RosConnectorObject and add the
StringSubsriber
script. Let's use/test
for the topic name and0
for the time step, which basically means to receive messages as fast as the publisher sends them. -
Now go to your terminal, open rosbridge and publish some messages.
ros2 launch rosbridge_server rosbridge_websocket_launch.xml
# Another terminal
ros2 topic pub /test std_msgs/msg/String "data: 'Hello ROS#'"
Adding an existing class is very easy, but how about writing one? That is, if not the same, also very easy! Note that there is a Float64 message type in RosSharp.RosBridgeClient.MessageTypes.Std
, but there is no Float64Publisher.cs
. Why is that? Because we do not want to increase package complexity, size and compile time for a message type you may never use.
- As we learned from the StringSubscriber, we first need to implement the
UnityPublisher
abstract class with the correct message type, which is<MessageTypes.Std.Float64>
this time.
using UnityEngine;
namespace RosSharp.RosBridgeClient
{
public class Float64Publisher : UnityPublisher<MessageTypes.Std.Float64>
{
public double DoubleData = 0;
private MessageTypes.Std.Float64 message;
...
- After declaring the necessary variables and calling the
Start
base method, since we are now the one creating the message, we need to additionally call theInitalizeMessage
method. This is the constructor for the<MessageTypes.Std.Float64>
message, i.e. theFloat64.cs
class.
...
protected override void Start()
{
base.Start();
InitializeMessage();
}
private void InitializeMessage()
{
message = new MessageTypes.Std.Float64
{
data = DoubleData
};
}
...
- After initialization, again using the built-in
FixedUpdate
method, we can publish the message at a fixed interval, as the name suggests. This time, however, there is no direct way to change the publishing rate as we had in theUnitySubscriber
class, i.e. theTime Step
variable. If the fixed time step in the Unity project settings is not suitable for you, i.e. maybe you are doing a simulation in Unity with a fixed physics time step of 2ms and 500 messages per second might be an unnecessary load for the rosbrige_server, you can implement a simple timer via e.g. System.Timers. But for the sake of this tutorial, let's keep things simple.
...
private void FixedUpdate()
{
UpdateMessage();
}
public void UpdateMessage()
{
message.data = DoubleData;
Publish(message);
Debug.Log("Published message: " + message.data);
}
}
}
-
Now add our freshly written script to the RosConnectorObject, then write your favorite topic name and double value.
-
Similary, launch the rosbridge_server from your terminal, run Unity, and subscribe to the topic.
ros2 launch rosbridge_server rosbridge_websocket_launch.xml
# Another terminal, after running Unity
ros2 topic echo /test
Next tutorial: Transfer a URDF from ROS to Unity
© Siemens AG, 2017-2024
-
- 1.3.1 R2D2 Setup
- 1.3.2 Gazebo Setup on VM
- 1.3.3 TurtleBot Setup (Optional for ROS2)
-
- 2.1 Quick Start
- 2.2 Transfer a URDF from ROS to Unity
- 2.3 Transfer a URDF from Unity to ROS
- 2.4 Unity Simulation Scene Example
- 2.5 Gazebo Simulation Scene Example
- 2.6 Fibonacci Action Client
- 2.7 Fibonacci Action Server
- 3.1 Import a URDF on Windows
- 3.2 Create, Modify and Export a URDF Model
- 3.3 Animate a Robot Model in Unity
- Message Handling: Readers & Writers
- Thread Safety for Message Reception
- File Server Package
- ROS-Unity Coordinate System Conversions
- Post Build Events
- Preprocessor Directives in ROS#
- Adding New Message Types
- RosBridgeClient Protocols
- RosBridgeClient Serializers
- Action Server State Machine Model
© Siemens AG, 2017-2024