-
Notifications
You must be signed in to change notification settings - Fork 374
/
RosSocketConsoleExample.cs
88 lines (72 loc) · 3.43 KB
/
RosSocketConsoleExample.cs
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
/*
© Siemens AG, 2017-2019
Author: Dr. Martin Bischoff ([email protected])
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
<http://www.apache.org/licenses/LICENSE-2.0>.
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
using System;
using RosSharp.RosBridgeClient;
using std_msgs = RosSharp.RosBridgeClient.MessageTypes.Std;
using std_srvs = RosSharp.RosBridgeClient.MessageTypes.Std;
using rosapi = RosSharp.RosBridgeClient.MessageTypes.Rosapi;
// commands on ROS system:
// launch before starting:
// roslaunch rosbridge_server rosbridge_websocket.launch
// rostopic echo /publication_test
// rostopic pub /subscription_test std_msgs/String "subscription test message data"
// launch after starting:
// rosservice call /service_response_test
namespace RosSharp.RosBridgeClientTest
{
public class RosSocketConsole
{
static readonly string uri = "ws://192.168.56.102:9090";
public static void Main(string[] args)
{
//RosSocket rosSocket = new RosSocket(new RosBridgeClient.Protocols.WebSocketSharpProtocol(uri));
RosSocket rosSocket = new RosSocket(new RosBridgeClient.Protocols.WebSocketNetProtocol(uri));
// Publication:
std_msgs.String message = new std_msgs.String
{
data = "publication test masdasdessage data"
};
string publication_id = rosSocket.Advertise<std_msgs.String>("publication_test");
rosSocket.Publish(publication_id, message);
// Subscription:
string subscription_id = rosSocket.Subscribe<std_msgs.String>("/subscription_test", SubscriptionHandler);
subscription_id = rosSocket.Subscribe<std_msgs.String>("/subscription_test", SubscriptionHandler);
// Service Call:
rosSocket.CallService<rosapi.GetParamRequest, rosapi.GetParamResponse>("/rosapi/get_param", ServiceCallHandler, new rosapi.GetParamRequest("/rosdistro", "default"));
// Service Response:
string service_id = rosSocket.AdvertiseService<std_srvs.TriggerRequest, std_srvs.TriggerResponse>("/service_response_test", ServiceResponseHandler);
Console.WriteLine("Press any key to unsubscribe...");
Console.ReadKey(true);
rosSocket.Unadvertise(publication_id);
rosSocket.Unsubscribe(subscription_id);
rosSocket.UnadvertiseService(service_id);
Console.WriteLine("Press any key to close...");
Console.ReadKey(true);
rosSocket.Close();
}
private static void SubscriptionHandler(std_msgs.String message)
{
Console.WriteLine((message).data);
}
private static void ServiceCallHandler(rosapi.GetParamResponse message)
{
Console.WriteLine("ROS distro: " + message.value);
}
private static bool ServiceResponseHandler(std_srvs.TriggerRequest arguments, out std_srvs.TriggerResponse result)
{
result = new std_srvs.TriggerResponse(true, "service response message");
return true;
}
}
}