-
Notifications
You must be signed in to change notification settings - Fork 1
/
ros.proto
314 lines (254 loc) · 6.06 KB
/
ros.proto
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
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
syntax = 'proto3';
package ros;
message Empty {}
message Time {
uint32 secs = 1;
uint32 nsecs = 2;
}
message Duration {
int32 secs = 1;
int32 nsecs = 2;
}
message actionlib_msgs {
message GoalID {
Time stamp = 1;
string id = 2;
}
/**
* PENDING=0
* ACTIVE=1
* PREEMPTED=2
* SUCCEEDED=3
* ABORTED=4
* REJECTED=5
* PREEMPTING=6
* RECALLING=7
* RECALLED=8
* LOST=9
*/
message GoalStatus {
actionlib_msgs.GoalID goal_id = 1;
uint32 status = 2;
string text = 3;
}
message GoalStatusArray {
std_msgs.Header header = 1;
repeated actionlib_msgs.GoalStatus status_list = 2;
}
}
message geometry_msgs {
message Twist {
geometry_msgs.Vector3 linear = 1;
geometry_msgs.Vector3 angular = 2;
}
message Vector3 {
double x = 1;
double y = 2;
double z = 3;
}
}
message roscpp {
message GetLoggersRequest {
}
message GetLoggersResponse {
repeated roscpp.Logger loggers = 1;
}
message Logger {
string name = 1;
string level = 2;
}
message SetLoggerLevelRequest {
string logger = 1;
string level = 2;
}
message SetLoggerLevelResponse {
}
}
message rosgraph_msgs {
/**
* DEBUG=1
* INFO=2
* WARN=4
* ERROR=8
* FATAL=16
*/
message Log {
std_msgs.Header header = 1;
int32 level = 2;
string name = 3;
string msg = 4;
string file = 5;
string function = 6;
uint32 line = 7;
repeated string topics = 8;
}
}
message std_msgs {
message Header {
uint32 seq = 1;
Time stamp = 2;
string frame_id = 3;
}
}
message std_srvs {
message EmptyRequest {
}
message EmptyResponse {
}
}
message turtle_actionlib {
message ShapeActionFeedback {
std_msgs.Header header = 1;
actionlib_msgs.GoalStatus status = 2;
turtle_actionlib.ShapeFeedback feedback = 3;
}
message ShapeActionGoal {
std_msgs.Header header = 1;
actionlib_msgs.GoalID goal_id = 2;
turtle_actionlib.ShapeGoal goal = 3;
}
message ShapeActionResult {
std_msgs.Header header = 1;
actionlib_msgs.GoalStatus status = 2;
turtle_actionlib.ShapeResult result = 3;
}
message ShapeFeedback {
}
message ShapeGoal {
int32 edges = 1;
float radius = 2;
}
message ShapeResult {
float interior_angle = 1;
float apothem = 2;
}
}
message turtlesim {
message Color {
uint32 r = 1;
uint32 g = 2;
uint32 b = 3;
}
message KillRequest {
string name = 1;
}
message KillResponse {
}
message Pose {
float x = 1;
float y = 2;
float theta = 3;
float linear_velocity = 4;
float angular_velocity = 5;
}
message SetPenRequest {
uint32 r = 1;
uint32 g = 2;
uint32 b = 3;
uint32 width = 4;
uint32 off = 5;
}
message SetPenResponse {
}
message SpawnRequest {
float x = 1;
float y = 2;
float theta = 3;
string name = 4;
}
message SpawnResponse {
string name = 1;
}
message TeleportAbsoluteRequest {
float x = 1;
float y = 2;
float theta = 3;
}
message TeleportAbsoluteResponse {
}
message TeleportRelativeRequest {
float linear = 1;
float angular = 2;
}
message TeleportRelativeResponse {
}
}
service rosout {
rpc Publish(rosgraph_msgs.Log) returns (Empty);
rpc Subscribe(Empty) returns (stream rosgraph_msgs.Log);
}
service rosout_agg {
rpc Publish(rosgraph_msgs.Log) returns (Empty);
rpc Subscribe(Empty) returns (stream rosgraph_msgs.Log);
}
service shapes_cancel {
rpc Publish(actionlib_msgs.GoalID) returns (Empty);
rpc Subscribe(Empty) returns (stream actionlib_msgs.GoalID);
}
service shapes_feedback {
rpc Publish(turtle_actionlib.ShapeActionFeedback) returns (Empty);
rpc Subscribe(Empty) returns (stream turtle_actionlib.ShapeActionFeedback);
}
service shapes_goal {
rpc Publish(turtle_actionlib.ShapeActionGoal) returns (Empty);
rpc Subscribe(Empty) returns (stream turtle_actionlib.ShapeActionGoal);
}
service shapes_result {
rpc Publish(turtle_actionlib.ShapeActionResult) returns (Empty);
rpc Subscribe(Empty) returns (stream turtle_actionlib.ShapeActionResult);
}
service shapes_status {
rpc Publish(actionlib_msgs.GoalStatusArray) returns (Empty);
rpc Subscribe(Empty) returns (stream actionlib_msgs.GoalStatusArray);
}
service turtle1_cmd_vel {
rpc Publish(geometry_msgs.Twist) returns (Empty);
rpc Subscribe(Empty) returns (stream geometry_msgs.Twist);
}
service turtle1_color_sensor {
rpc Publish(turtlesim.Color) returns (Empty);
rpc Subscribe(Empty) returns (stream turtlesim.Color);
}
service turtle1_pose {
rpc Publish(turtlesim.Pose) returns (Empty);
rpc Subscribe(Empty) returns (stream turtlesim.Pose);
}
service clear {
rpc Call(std_srvs.EmptyRequest) returns (std_srvs.EmptyResponse);
}
service kill {
rpc Call(turtlesim.KillRequest) returns (turtlesim.KillResponse);
}
service reset {
rpc Call(std_srvs.EmptyRequest) returns (std_srvs.EmptyResponse);
}
service rosout_get_loggers {
rpc Call(roscpp.GetLoggersRequest) returns (roscpp.GetLoggersResponse);
}
service rosout_set_logger_level {
rpc Call(roscpp.SetLoggerLevelRequest) returns (roscpp.SetLoggerLevelResponse);
}
service shapes_get_loggers {
rpc Call(roscpp.GetLoggersRequest) returns (roscpp.GetLoggersResponse);
}
service shapes_set_logger_level {
rpc Call(roscpp.SetLoggerLevelRequest) returns (roscpp.SetLoggerLevelResponse);
}
service sim_get_loggers {
rpc Call(roscpp.GetLoggersRequest) returns (roscpp.GetLoggersResponse);
}
service sim_set_logger_level {
rpc Call(roscpp.SetLoggerLevelRequest) returns (roscpp.SetLoggerLevelResponse);
}
service spawn {
rpc Call(turtlesim.SpawnRequest) returns (turtlesim.SpawnResponse);
}
service turtle1_set_pen {
rpc Call(turtlesim.SetPenRequest) returns (turtlesim.SetPenResponse);
}
service turtle1_teleport_absolute {
rpc Call(turtlesim.TeleportAbsoluteRequest) returns (turtlesim.TeleportAbsoluteResponse);
}
service turtle1_teleport_relative {
rpc Call(turtlesim.TeleportRelativeRequest) returns (turtlesim.TeleportRelativeResponse);
}