forked from pf-robotics/kachaka-api
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathkachaka-api.proto
670 lines (562 loc) · 15.6 KB
/
kachaka-api.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
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
// Copyright 2023 Preferred Robotics, Inc.
//
// 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.
syntax = "proto3";
package kachaka_api;
// Common messages
message Metadata {
sfixed64 cursor = 1;
}
message Result {
bool success = 1;
int32 error_code = 3;
}
message Error {
int32 error_code = 2;
}
message RosHeader {
int64 stamp_nsec = 1;
string frame_id = 2;
}
message Pose {
double x = 1;
double y = 2;
double theta = 3;
}
message Vector3 {
double x = 1;
double y = 2;
double z = 3;
}
message Quaternion {
double x = 1;
double y = 2;
double z = 3;
double w = 4;
}
message Pose3d {
Vector3 position = 1;
Quaternion orientation = 2;
}
message Twist {
Vector3 linear = 1;
Vector3 angular = 2;
}
message Pose3dWithCovariance {
Pose3d pose = 1;
repeated double covariance = 2;
}
message TwistWithCovariance {
Twist twist = 1;
repeated double covariance = 2;
}
enum PowerSupplyStatus {
POWER_SUPPLY_STATUS_UNSPECIFIED = 0;
POWER_SUPPLY_STATUS_CHARGING = 1;
POWER_SUPPLY_STATUS_DISCHARGING = 2;
POWER_SUPPLY_STATUS_NOT_CHARGING = 3;
POWER_SUPPLY_STATUS_FULL = 4;
}
message Map {
bytes data = 1; // uint8[]
string name = 2;
double resolution = 3;
int32 width = 4; // larger than 0
int32 height = 5; // larger than 0
Pose origin = 6;
}
enum LocationType {
LOCATION_TYPE_UNSPECIFIED = 0; // normal location
LOCATION_TYPE_CHARGER = 1;
LOCATION_TYPE_SHELF_HOME = 2;
}
message Location {
string id = 1;
string name = 2;
Pose pose = 3; // relative to map origin
LocationType type = 4;
bool undock_shelf_aligning_to_wall = 5;
bool undock_shelf_avoiding_obstacles = 6;
bool ignore_voice_recognition = 7;
}
message ShelfSize {
double width = 1;
double depth = 2;
double height = 3;
}
enum ShelfAppearance {
SHELF_APPEARANCE_UNSPECIFIED = 0;
SHELF_APPEARANCE_DEFAULT_SHELF = 1;
SHELF_APPEARANCE_KACHAKA_SHELF_3DRAWERS = 2;
SHELF_APPEARANCE_KACHAKA_SHELF_2DRAWERS = 3;
SHELF_APPEARANCE_KACHAKA_BASE = 8;
}
enum ShelfSpeedMode {
SHELF_SPEED_MODE_UNSPECIFIED = 0;
SHELF_SPEED_MODE_LOW = 1;
SHELF_SPEED_MODE_NORMAL = 2;
}
message RecognizableName {
string name = 1;
bool deletable = 2;
}
message Shelf {
string id = 1;
string name = 2;
Pose pose = 3; // relative to map origin
ShelfSize size = 4;
ShelfAppearance appearance = 5;
repeated RecognizableName recognizable_names = 7; // Recognizable by speech recognition.
string home_location_id = 8;
ShelfSpeedMode speed_mode = 9;
bool ignore_voice_recognition = 10;
}
message RosImu {
RosHeader header = 1;
Quaternion orientation = 2;
repeated double orientation_covariance = 3;
Vector3 angular_velocity = 4;
repeated double angular_velocity_covariance = 5;
Vector3 linear_acceleration = 6;
repeated double linear_acceleration_covariance = 7;
}
message RosOdometry {
RosHeader header = 1;
string child_frame_id = 2;
Pose3dWithCovariance pose = 3;
TwistWithCovariance twist = 4;
}
message RosLaserScan {
RosHeader header = 1;
double angle_min = 2;
double angle_max = 3;
double angle_increment = 4;
double time_increment = 5;
double scan_time = 6;
double range_min = 7;
double range_max = 8;
repeated double ranges = 9;
repeated double intensities = 10;
}
message RegionOfInterest {
uint32 x_offset = 1;
uint32 y_offset = 2;
uint32 height = 3;
uint32 width = 4;
bool do_rectify = 5;
}
message RosCameraInfo {
RosHeader header = 1;
uint32 height = 2;
uint32 width = 3;
string distortion_model = 4;
repeated double D = 5;
repeated double K = 6;
repeated double R = 7;
repeated double P = 8;
uint32 binning_x = 9;
uint32 binning_y = 10;
RegionOfInterest roi = 11;
}
message RosImage {
RosHeader header = 1;
uint32 height = 2;
uint32 width = 3;
string encoding = 4;
bool is_bigendian = 5;
uint32 step = 6;
bytes data = 7;
}
message RosTransformStamped {
RosHeader header = 1;
string child_frame_id = 2;
Vector3 translation = 3;
Quaternion rotation = 4;
}
message RosCompressedImage {
RosHeader header = 1;
string format = 2;
bytes data = 3;
}
enum ObjectLabel {
OBJECT_LABEL_UNSPECIFIED = 0;
OBJECT_LABEL_PERSON = 1;
OBJECT_LABEL_SHELF = 2;
OBJECT_LABEL_CHARGER = 3;
OBJECT_LABEL_DOOR = 4;
}
message ObjectDetection {
uint32 label = 1;
RegionOfInterest roi = 2;
float score = 3;
double distance_median = 4;
}
message ObjectDetectionFeatures {
string name = 1;
repeated uint32 shape = 2;
repeated float data = 3;
}
// Commands
message Command {
oneof command {
MoveShelfCommand move_shelf_command = 1;
ReturnShelfCommand return_shelf_command = 2;
UndockShelfCommand undock_shelf_command = 5;
MoveToLocationCommand move_to_location_command = 7;
ReturnHomeCommand return_home_command = 8;
DockShelfCommand dock_shelf_command = 9;
SpeakCommand speak_command = 12;
MoveToPoseCommand move_to_pose_command = 13;
LockCommand lock_command = 15;
MoveForwardCommand move_forward_command = 16;
RotateInPlaceCommand rotate_in_place_command = 17;
}
}
message MoveShelfCommand {
string target_shelf_id = 1;
string destination_location_id = 2;
}
message ReturnShelfCommand {
string target_shelf_id = 1;
}
message UndockShelfCommand {
// target_shelf_id can remain unset at the time of the request. It is filled
// in when retrieving the status or result of the issued command to identify
// which shelf was undocked. See GetLastCommandResultResponse for reference.
string target_shelf_id = 1;
}
message MoveToLocationCommand {
string target_location_id = 1;
}
message ReturnHomeCommand {
}
message DockShelfCommand {
}
message SpeakCommand {
string text = 1;
}
message MoveToPoseCommand {
double x = 1;
double y = 2;
double yaw = 3;
}
message LockCommand {
double duration_sec = 1;
}
message MoveForwardCommand {
double distance_meter = 1;
}
message RotateInPlaceCommand {
double angle_radian = 1;
}
enum CommandState {
COMMAND_STATE_UNSPECIFIED = 0;
COMMAND_STATE_PENDING = 1; // No command is running. Waiting for requests.
COMMAND_STATE_RUNNING = 2;
}
// Requests and Responses
message EmptyRequest {
}
message GetRequest {
Metadata metadata = 1;
}
message GetRobotSerialNumberResponse {
Metadata metadata = 1;
string serial_number = 2;
}
message GetRobotVersionResponse {
Metadata metadata = 1;
string version = 2;
}
message GetRobotPoseResponse {
Metadata metadata = 1;
Pose pose = 2;
}
message GetBatteryInfoResponse {
Metadata metadata = 1;
double remaining_percentage = 2; // [0, 100]
PowerSupplyStatus power_supply_status = 3;
}
message GetPngMapResponse {
Metadata metadata = 1;
Map map = 2;
}
message GetObjectDetectionResponse {
Metadata metadata = 1;
RosHeader header = 2;
repeated ObjectDetection objects = 3;
}
message GetObjectDetectionFeaturesResponse {
Metadata metadata = 1;
RosHeader header = 2;
repeated ObjectDetectionFeatures features = 3;
}
message GetRosImuResponse {
Metadata metadata = 1;
RosImu imu = 2;
}
message GetRosOdometryResponse {
Metadata metadata = 1;
RosOdometry odometry = 2;
}
message GetRosLaserScanResponse {
Metadata metadata = 1;
RosLaserScan scan = 2;
}
message GetFrontCameraRosCameraInfoResponse {
Metadata metadata = 1;
RosCameraInfo camera_info = 2;
}
message GetFrontCameraRosImageResponse {
Metadata metadata = 1;
RosImage image = 2;
}
message GetFrontCameraRosCompressedImageResponse {
Metadata metadata = 1;
RosCompressedImage image = 2;
}
message GetBackCameraRosCameraInfoResponse {
Metadata metadata = 1;
RosCameraInfo camera_info = 2;
}
message GetBackCameraRosImageResponse {
Metadata metadata = 1;
RosImage image = 2;
}
message GetBackCameraRosCompressedImageResponse {
Metadata metadata = 1;
RosCompressedImage image = 2;
}
message GetTofCameraRosCameraInfoResponse {
Metadata metadata = 1;
RosCameraInfo camera_info = 2;
}
message GetTofCameraRosImageResponse {
Metadata metadata = 1;
RosImage image = 2;
bool is_available = 3;
}
message GetTofCameraRosCompressedImageResponse {
Metadata metadata = 1;
RosCompressedImage image = 2;
bool is_available = 3;
}
message StartCommandRequest {
Command command = 1;
bool cancel_all = 2;
string tts_on_success = 3;
string title = 4;
bool deferrable = 5;
}
message StartCommandResponse {
Result result = 1;
string command_id = 2;
}
message CancelCommandResponse {
Result result = 1;
Command command = 2;
}
message GetCommandStateResponse {
Metadata metadata = 1;
CommandState state = 2;
Command command = 3;
string command_id = 4;
}
message GetLastCommandResultResponse {
Metadata metadata = 1;
Result result = 2; // Empty if there is no last command
Command command = 3;
string command_id = 4;
}
message ProceedResponse {
Result result = 1;
}
message GetLocationsResponse {
Metadata metadata = 1;
repeated Location locations = 2;
string default_location_id = 3;
}
message GetShelvesResponse {
Metadata metadata = 1;
repeated Shelf shelves = 2;
}
message GetMovingShelfIdResponse {
Metadata metadata = 1;
string shelf_id = 2; // Empty if no shelf
}
message ResetShelfPoseRequest {
string shelf_id = 1; // If empty, resetting all shelves
}
message ResetShelfPoseResponse {
Result result = 1;
}
message SetAutoHomingEnabledRequest {
bool enable = 1;
}
message SetAutoHomingEnabledResponse {
Result result = 1;
}
message GetAutoHomingEnabledResponse {
Metadata metadata = 1;
bool enabled = 2;
}
message SetManualControlEnabledRequest {
bool enable = 1;
bool use_shelf_registration = 2; // effective only if enable==true
}
message SetManualControlEnabledResponse {
Result result = 1;
}
message GetManualControlEnabledResponse {
Metadata metadata = 1;
bool enabled = 2;
}
message SetFrontTorchIntensityRequest {
int32 intensity = 1; // [0, 255]
}
message SetFrontTorchIntensityResponse {
Result result = 1;
}
message SetBackTorchIntensityRequest {
int32 intensity = 1; // [0, 255]
}
message SetBackTorchIntensityResponse {
Result result = 1;
}
message SetRobotVelocityRequest {
double linear = 1; // [-1, 1]
double angular = 2; // [-1, 1]
}
message SetRobotVelocityResponse {
Result result = 1;
}
message ActivateLaserScanRequest {
double duration_sec = 1;
}
message ActivateLaserScanResponse {
Result result = 1;
}
message GetStaticTransformResponse {
Metadata metadata = 1;
repeated RosTransformStamped transforms = 2;
}
message GetDynamicTransformResponse {
repeated RosTransformStamped transforms = 1;
}
// Map
message MapListEntry {
string id = 2;
string name = 1;
}
message GetMapListResponse {
Metadata metadata = 1;
repeated MapListEntry map_list_entries = 2;
}
message GetCurrentMapIdResponse {
Metadata metadata = 1;
string id = 2; // empty if no map is available
}
message LoadMapPreviewRequest {
string map_id = 1;
}
message LoadMapPreviewResponse {
Result result = 1;
Map map = 2;
}
message ExportMapRequest {
string map_id = 1;
}
message ExportMapResponse {
message MiddleOfStream {
bytes data = 1;
}
message EndOfStream {
Result result = 1;
}
oneof response {
MiddleOfStream middle_of_stream = 1;
EndOfStream end_of_stream = 2;
}
}
message ImportMapRequest {
bytes data = 1;
}
message ImportMapResponse {
Result result = 1;
string map_id = 2;
}
// History
message History {
string id = 1;
Command command = 4;
bool success = 5;
int32 error_code = 6;
int64 command_executed_time = 7;
}
message GetHistoryListResponse {
Metadata metadata = 1;
repeated History histories = 2;
}
message SwitchMapRequest {
string map_id = 1;
Pose initial_pose = 2; // use the charger pose if the message is empty
}
message SwitchMapResponse {
Result result = 1;
}
// Services
service KachakaApi {
rpc GetRobotSerialNumber (GetRequest) returns (GetRobotSerialNumberResponse);
rpc GetRobotVersion (GetRequest) returns (GetRobotVersionResponse);
rpc GetRobotPose (GetRequest) returns (GetRobotPoseResponse);
rpc GetBatteryInfo (GetRequest) returns (GetBatteryInfoResponse);
rpc GetPngMap (GetRequest) returns (GetPngMapResponse);
rpc GetObjectDetection (GetRequest) returns (GetObjectDetectionResponse);
rpc GetObjectDetectionFeatures (GetRequest) returns (GetObjectDetectionFeaturesResponse);
rpc GetRosImu (GetRequest) returns (GetRosImuResponse);
rpc GetRosOdometry (GetRequest) returns (GetRosOdometryResponse);
rpc GetRosLaserScan (GetRequest) returns (GetRosLaserScanResponse);
rpc GetFrontCameraRosCameraInfo (GetRequest) returns (GetFrontCameraRosCameraInfoResponse);
rpc GetFrontCameraRosImage (GetRequest) returns (GetFrontCameraRosImageResponse);
rpc GetFrontCameraRosCompressedImage (GetRequest) returns (GetFrontCameraRosCompressedImageResponse);
rpc GetBackCameraRosCameraInfo (GetRequest) returns (GetBackCameraRosCameraInfoResponse);
rpc GetBackCameraRosImage (GetRequest) returns (GetBackCameraRosImageResponse);
rpc GetBackCameraRosCompressedImage (GetRequest) returns (GetBackCameraRosCompressedImageResponse);
rpc GetTofCameraRosCameraInfo (GetRequest) returns (GetTofCameraRosCameraInfoResponse);
rpc GetTofCameraRosImage (GetRequest) returns (GetTofCameraRosImageResponse);
rpc GetTofCameraRosCompressedImage (GetRequest) returns (GetTofCameraRosCompressedImageResponse);
rpc StartCommand (StartCommandRequest) returns (StartCommandResponse);
rpc CancelCommand (EmptyRequest) returns (CancelCommandResponse);
rpc GetCommandState (GetRequest) returns (GetCommandStateResponse);
rpc GetLastCommandResult (GetRequest) returns (GetLastCommandResultResponse);
rpc Proceed (EmptyRequest) returns (ProceedResponse);
rpc GetLocations (GetRequest) returns (GetLocationsResponse);
rpc GetShelves (GetRequest) returns (GetShelvesResponse);
rpc GetMovingShelfId (GetRequest) returns (GetMovingShelfIdResponse);
rpc ResetShelfPose (ResetShelfPoseRequest) returns (ResetShelfPoseResponse);
rpc SetAutoHomingEnabled (SetAutoHomingEnabledRequest) returns (SetAutoHomingEnabledResponse);
rpc GetAutoHomingEnabled (GetRequest) returns (GetAutoHomingEnabledResponse);
rpc SetManualControlEnabled (SetManualControlEnabledRequest) returns (SetManualControlEnabledResponse);
rpc GetManualControlEnabled (GetRequest) returns (GetManualControlEnabledResponse);
rpc SetFrontTorchIntensity (SetFrontTorchIntensityRequest) returns (SetFrontTorchIntensityResponse);
rpc SetBackTorchIntensity (SetBackTorchIntensityRequest) returns (SetBackTorchIntensityResponse);
rpc SetRobotVelocity (SetRobotVelocityRequest) returns (SetRobotVelocityResponse);
rpc ActivateLaserScan (ActivateLaserScanRequest) returns (ActivateLaserScanResponse);
rpc GetMapList (GetRequest) returns (GetMapListResponse);
rpc GetCurrentMapId (GetRequest) returns (GetCurrentMapIdResponse);
rpc LoadMapPreview (LoadMapPreviewRequest) returns (LoadMapPreviewResponse);
rpc ExportMap (ExportMapRequest) returns (stream ExportMapResponse);
rpc ImportMap (stream ImportMapRequest) returns (ImportMapResponse);
rpc GetHistoryList (GetRequest) returns (GetHistoryListResponse);
rpc GetStaticTransform (GetRequest) returns (GetStaticTransformResponse);
rpc GetDynamicTransform (EmptyRequest) returns (stream GetDynamicTransformResponse);
rpc SwitchMap (SwitchMapRequest) returns (SwitchMapResponse);
}