Skip to content

Dev_NewMessageTypes

Berkay Alp Cakal edited this page Mar 27, 2020 · 10 revisions

How to add new Message Types

This wiki page aims to explain how to add new message types in ROS#.

Some general remarks

  • All ROS# messages and services are defined under the namespace the RosSharp.RosBridgeClient.Message, and they implement the abstract class Message.cs.

  • All ROS# messages have a constant string called RosMessageName as the class property, which indicates their names in ROS (e.g. "sensor_msgs/JointState", "std_msgs/Float32"). Other message fields should be C# class properties (required by the .NET JSON serialization API). Make sure that field names are consistent on both ROS and ROS# side, especially the lowercase/uppercases letters.

  • ROS services consist of a Request and a Response. In ROS#, they are separated into two different classes. For example, std_srvs/SetBool will be split into SetBoolRequest and SetBoolResponse.

  • ROS actions consist of a goal, a result and a feedback. Following the ROS conventions of generating action messages, in ROS# action messages are split into 7 classes. For example, messages of actionlib_tutorials/Fibonacci will be split into FibonacciAction, FibonacciGoal, FibonacciActionGoal, FibonacciResult, FibonacciActionResult, FibonacciFeedback and FibonacciActionFeedback message classes.

  • Generated action message classes inherit corresponding base classes under Libraries/RosBridgeClient/BaseMessages/Actions.

  • Messages, services and actions will get their own folder after generation, under the folder named after their package name. For example, Nav/msg and Nav/srv.

  • Naming message fields with words which are actually the C# keywords should be avoided.

Option 1: Generate Message Types in Unity3D using local ROS message files

Select the appropriate submenu under the RosBridgeClient > Auto Generate Messages/Services/Actions menu, depending on the input file type. You can choose to generate a single message, messages of a package or all messages under a directory.

1. Single message

In the editor window, find your target by Browse File... and once the message file is selected, the package name will be extracted assuming the ROS folder structure, but you can set the package name manually as well.

The default output folder is Assests/RosSharpMessages, but you can change it by Select Folder...

When you are ready, just hit GENERATE! and C# script for the message will be ready for you, under RosSharpMessages/PackageName

2. Package message

A similar procedure is applied here. The only difference is that this time, you will be selecting the folder of your ROS package, and the message files will be found.

When you are ready, hit GENERATE!

3. Directory message

The tool will take over package naming since there are probably more than one package under the directory.

Just select the folder that contains all the messages you want to generate, click GENERATE!.

Option 2: Use a console tool with local ROS message files

It is possible to generate custom messages without Unity3D. You can use your favorite console tool to auto generate custom messages.

1. 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

2. Open a terminal

  • On your terminal, navigate to ..Libraries/MessageGenerationConsoleTool/bin/Release
  • Enter ./RosMsgGen.exe to see instructions;
  • Add the following flags to enable different functions
    • -v or --verbose Outputs extra information
    • -s or --service Generate service messages
    • -a or --action Generate action messages
    • -r or --recursive Generate message for all ROS message files in the specified directory
    • -p or --package Treat the directory as a single ROS package during message generation
    • -n or --ros-package-name Specify the ROS package name for the message
    • -o or --output Specify output path
  • For example:
    • Generate a single message at the current directory: ./RosMsgGen.exe <input file>
    • Generate a package service at a chosen directory: ./RosMsgGen.exe -p -s <input directory> -o <output directory>
    • Generate actions under a directory with verbose at the current directory: /RosMsgGen.exe -v -r -a <input directory>

Option 3: Manually generate messages via RosbridgeClient library

1. Declare a new message type

Add a new class in Libraries\RosBridgeClient\MessageTypes or any of its subfolders, and make it extend the Message class. Here is an example code for "std_msgs/Float32";

namespace RosSharp.RosBridgeClient.MessageTypes.Std
{
    public class Float32 : Message
    {
        public const string RosMessageName = "std_msgs/Float32";
        public float data {get; set;}

        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\

4. Use the new MessageType in your Unity Project

You can create a publisher or a subscriber script under the folder Assets\RosSharp\Scripts\RosCommunication;

Example Publisher Script:

namespace RosSharp.RosBridgeClient
{
    public class FloatPublisher : UnityPublisher<MessageTypes.Std.Float32>
    {
        public float messageData;

        private MessageTypes.Std.Float32 message;

        protected override void Start()
        {
            base.Start();
            InitializeMessage();
        }

        private void InitializeMessage()
        {
            message = new MessageTypes.Std.Float32
            {
                data = messageData
            };
        }

        private void Update()
        {
            message.data = messageData;
            Publish(message);
        }
    }
}

Example Subscriber Script:

namespace RosSharp.RosBridgeClient
{
    public class FloatSubscriber : UnitySubscriber<MessageTypes.Std.Float32>
    {
        public float messageData;

        protected override void Start()
        {
            base.Start();
        }

        protected override void ReceiveMessage(MessageTypes.Std.Float32 message)
        {
            messageData = message.data;
        }
    }
}

© Siemens AG, 2017-2020 Author: Sifan Ye (sifan.ye@siemens.com)

Clone this wiki locally