-
Notifications
You must be signed in to change notification settings - Fork 373
User_App_DotNet_Intro_RosBridgeClient
The RosBridgeClient is a powerful .NET library that enables seamless communication between your .NET application and the ROS ecosystem. With ROSBridgeClient, you can easily publish and subscribe to ROS topics, handle service calls, and respond to service requests.
This guide will walk you through the essential steps to get started with the ROSBridgeClient library. You will learn how to set up the ROSBridge server, establish a ROS socket connection, publish and subscribe to topics, handle service calls, and respond to service requests.
4.1.1 Setting Up the ROSBridge Server 4.1.2 Creating a ROS Socket 4.1.3 Publishing a Topic 4.1.4 Subscribing to a Topic 4.1.5 Handling Service Calls 4.1.6 Responding to Service Requests 4.1.7 Cleaning Up
Ensure the RosBridge server is running on the ROS machine. This allows your .NET application to interact with ROS topics and services. Refer to the 1. Installation and Configuration section for specific instructions.
The first step in your application is to establish a connection with the RosBridge server using the RosSocket
class. This socket will serve as the communication bridge between your .NET application and the ROS ecosystem.
Code Example:
using System;
using RosSharp.RosBridgeClient;
namespace RosSharpExample
{
public class Program
{
private static readonly string uri = "ws://localhost:9090";
public static void Main(string[] args)
{
// Establish a connection to the RosBridge server
RosSocket rosSocket = new RosSocket(new RosBridgeClient.Protocols.WebSocketNetProtocol(uri));
// Add your publishing/subscribing logic here
// Close the connection when done
rosSocket.Close();
}
}
}
-
URI: This string represents the WebSocket address of the RosBridge server. Adjust the
localhost
to the appropriate IP if connecting to a remote ROS system.
To publish a message to a ROS topic, you first need to advertise the topic, then create a message of the appropriate type, and finally publish that message.
Code Example:
using std_msgs = RosSharp.RosBridgeClient.MessageTypes.Std;
public static void PublishExample(RosSocket rosSocket)
{
// Create a message object
std_msgs.String message = new std_msgs.String
{
data = "Hello ROS from .NET!"
};
// Advertise the topic
string publication_id = rosSocket.Advertise<std_msgs.String>("<topic_name>");
// Publish the message
rosSocket.Publish(publication_id, message);
Console.WriteLine("Published message: " + message.data);
}
-
std_msgs.String: This is a predefined message type in ROS# corresponding to ROS's
std_msgs/String
. - Advertise: Registers the topic with ROS, specifying the type of messages it will carry.
Subscribing to a ROS topic allows your application to receive messages whenever they are published on that topic. This is particularly useful for listening to sensor data or receiving updates from other nodes.
Steps:
- Subscribe to the Topic: Register a callback method that will handle incoming messages.
- Define a Handler: Create a method that processes the received messages.
Code Example:
public static void SubscribeExample(RosSocket rosSocket)
{
// Subscribe to a topic
string subscription_id = rosSocket.Subscribe<std_msgs.String>("/<incoming_topic_name>", SubscriptionHandler);
}
// Handler method for incoming messages
private static void SubscriptionHandler(std_msgs.String message)
{
Console.WriteLine("Received message: " + message.data);
}
- SubscriptionHandler: This callback method processes each incoming message.
ROS services allow you to perform request/response communication between nodes. In ROS#, you can call a service and process the response using the CallService
method.
Steps:
- Call the Service: Specify the service name, the request type, and a callback to handle the response.
- Handle the Response: Define the callback method to process the response.
Code Example:
using rosapi = RosSharp.RosBridgeClient.MessageTypes.Rosapi;
public static void CallServiceExample(RosSocket rosSocket)
{
// Call a service and handle the response
rosSocket.CallService<rosapi.GetParamRequest, rosapi.GetParamResponse>(
"/rosapi/get_param",
ServiceCallHandler,
new rosapi.GetParamRequest("/rosdistro", "default_value") // Just "default" for ROS1
);
}
// Callback for handling service response
private static void ServiceCallHandler(rosapi.GetParamResponse message)
{
Console.WriteLine("Received ROS distro: " + message.value);
}
-
rosapi.GetParamRequest: Represents the request message for the
get_param
service in ROS. - ServiceCallHandler: A method that processes the service response.
Sometimes, your .NET application may need to act as a service provider. This involves responding to service requests from other ROS nodes.
Steps:
- Advertise the Service: Notify ROS that your application can handle a specific service request.
- Define the Service Handler: Implement the logic that processes incoming service requests and sends back a response.
Code Example:
public static void AdvertiseServiceExample(RosSocket rosSocket)
{
// Advertise a service
string service_id = rosSocket.AdvertiseService<rosapi.GetParamRequest, rosapi.GetParamResponse>(
"/my_service",
ServiceHandler
);
}
// Handler method for service requests
private static bool ServiceHandler(rosapi.GetParamRequest request, out rosapi.GetParamResponse response)
{
Console.WriteLine("Received request: " + request.name);
// Process request and create response
response = new rosapi.GetParamResponse
{
value = "response_value"
};
return true; // Indicates successful handling
}
- AdvertiseService: Registers your service with ROS, allowing it to receive and respond to requests.
- ServiceHandler: Processes incoming requests and generates appropriate responses.
- Unadvertise Topics: Unregister any topics your application was publishing to.
- Unsubscribe from Topics: Unregister any subscriptions.
- Unadvertise Services: Unregister any services.
- Close the ROS Socket: Gracefully close the WebSocket connection to the ROSBridge server.
Code Example:
public static void CleanUp(RosSocket rosSocket, string publicationId, string subscriptionId)
{
// Unadvertise the topic
rosSocket.Unadvertise(publicationId);
// Unsubscribe from the topic
rosSocket.Unsubscribe(subscriptionId);
// Unadvertise the service
rosSocket.UnadvertiseService(serviceId);
// Close the ROS socket connection
rosSocket.Close();
Console.WriteLine("Cleaned up ROS connections");
}
In the ROS# .NET solution you will see the RosBridgeClientTest project. For executable implementation examples, see the console examples in this project.
Next tutorial: Image Publication
© 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