-
Notifications
You must be signed in to change notification settings - Fork 370
Dev_NewMessageTypes
Martin Bischoff edited this page Jun 28, 2019
·
13 revisions
- Via the
RosBridgeClient > Generate Messages
menu.
The following editor window creates action messages which are used in actionlib tutorials .
Add a new class in Libraries\RosBridgeClient\Messages
or any of its subfolders, and make it extend the Message class.
using Newtonsoft.Json;
namespace RosSharp.RosBridgeClient.Messages.Standard
{
public class Float32 : Message
{
[JsonIgnore]
public const string RosMessageName = "std_msgs/Float32";
public float data;
public Float32()
{
data = 0;
}
}
}
2. Build RosSharp.sln in Visual Studio
- Open
Libraries\RosSharp.sln
in Visual Studio - In Build > Configuration Manager select:
- Active Solution Configuration: Release
- Active Solution Platform: Any CPU
- Click Build > Build Solution
3. Update RosBridgeClient.dll in your Unity Project
Copy RosBridgeClient.dll
- from
..Libraries\RosBridgeClient\bin\Release\
- to
...\Unity3D\Assets\RosSharp\Plugins\
Create a new script in Assets\RosSharp\Scripts\RosCommunication
.
Example Publisher Script:
namespace RosSharp.RosBridgeClient
{
public class FloatPublisher : Publisher<Messages.Standard.Float32>
{
public float messageData;
private Messages.Standard.Float32 message;
protected override void Start()
{
base.Start();
InitializeMessage();
}
private void InitializeMessage()
{
message = new Messages.Standard.Float32
{
data = messageData
};
}
private void Update()
{
message.data = messageData;
Publish(message);
}
}
}
Example Subscriber Script:
namespace RosSharp.RosBridgeClient
{
public class FloatSubscriber : Subscriber<Messages.Standard.Float32>
{
public float messageData;
protected override void Start()
{
base.Start();
}
protected override void ReceiveMessage(Messages.Standard.Float32 message)
{
messageData = message.data;
}
}
}
© Siemens AG, 2017-2019 Author: Suzannah Smith (suzannah.smith@siemens.com)
-
- 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