-
Notifications
You must be signed in to change notification settings - Fork 562
/
Copy pathworld_object.proto
405 lines (338 loc) · 15.1 KB
/
world_object.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
// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved.
//
// Downloading, reproducing, distributing or otherwise using the SDK Software
// is subject to the terms and conditions of the Boston Dynamics Software
// Development Kit License (20191101-BDSDK-SL).
syntax = "proto3";
package bosdyn.api;
option java_outer_classname = "WorldObjectProto";
import "bosdyn/api/docking/docking.proto";
import "bosdyn/api/geometry.proto";
import "bosdyn/api/header.proto";
import "bosdyn/api/image.proto";
import "bosdyn/api/sparse_features.proto";
import "bosdyn/api/stairs.proto";
import "bosdyn/api/gps/registration.proto";
import "google/protobuf/duration.proto";
import "google/protobuf/timestamp.proto";
import "google/protobuf/any.proto";
// The world object message is used to describe different objects seen by a robot. It contains
// information about the properties of the object in addition to a unique id and the transform
// snapshot. The world object uses "properties" to describe different traits about the object, such
// as image coordinates associated with the camera the object was detected in. A world object can
// have multiple different properties that are all associated with the single object.
message WorldObject {
// Unique integer identifier that will be consistent for the duration of a robot's battery life
// The id is set internally by the world object service.
int32 id = 1;
// A human readable name for the world object. Note that this differs from any frame_name's
// associated with the object (since there can be multiple frames describing a single object).
string name = 2;
// Time in robot time clock at which this object was most recently detected and valid.
google.protobuf.Timestamp acquisition_time = 30;
// A tree-based collection of transformations, which will include the transformations to each
// of the returned world objects in addition to transformations to the common frames ("vision",
// "body", "odom"). All transforms within the snapshot are at the acquisition time of the world
// object. Note that each object's frame names are defined within the properties submessage. For
// example, the apriltag frame name is defined in the AprilTagProperties message as
// "frame_name_fiducial"
FrameTreeSnapshot transforms_snapshot = 31;
// Duration of time after which the obstacle expires. If this field is left blank, the object
// will expire according to a default time set in the world object service. The duration is
// relative to the acquisition_time if filled out, or relative to the time the object is
// added to the world object service if acquisition_time is left blank.
google.protobuf.Duration object_lifetime = 32;
// The drawable properties describe geometric shapes associated with an object.
repeated DrawableProperties drawable_properties = 5;
// The apriltag properties describe any fiducial identifying an object.
AprilTagProperties apriltag_properties = 6;
// Property for a user no-go
NoGoRegionProperties nogo_region_properties = 14;
// The image properties describe any camera and image coordinates associated with an object.
ImageProperties image_properties = 9;
// Properties describing a dock
DockProperties dock_properties = 10;
// A ray pointing at the object. Useful in cases where position is unknown but direction is
// known.
RayProperties ray_properties = 11;
// Bounding box in the world, oriented at the location provided in the transforms_snapshot.
BoundingBoxProperties bounding_box_properties = 12;
// The staircase properties provide information that helps the robot traverse or see a
// staircase.
StaircaseProperties staircase_properties = 15;
// Information about the Earth relative to the robot, localized by GPS.
GpsProperties gps_properties = 16;
// An extra field for application-specific object properties.
google.protobuf.Any additional_properties = 100;
}
// A type for the world object, which is associated with whatever properties the world object
// includes. This can be used to request specific kinds of objects; for example, a request for only
// fiducials.
enum WorldObjectType {
WORLD_OBJECT_UNKNOWN = 0;
WORLD_OBJECT_DRAWABLE = 1;
WORLD_OBJECT_APRILTAG = 2;
WORLD_OBJECT_IMAGE_COORDINATES = 5;
WORLD_OBJECT_DOCK = 6;
WORLD_OBJECT_USER_NOGO = 8;
WORLD_OBJECT_STAIRCASE = 9;
}
// The ListWorldObject request message, which can optionally include filters for the object type or
// timestamp.
message ListWorldObjectRequest {
// Common request header
RequestHeader header = 1;
// Optional filters to apply to the world object request
// Specific type of object; can request multiple different properties
repeated WorldObjectType object_type = 2;
// Timestamp to filter objects based on. The time should be in robot time
// All objects with header timestamps after (>) timestamp_filter will be returned
google.protobuf.Timestamp timestamp_filter = 3;
}
// The ListWorldObject response message, which contains all of the current world objects in the
// robot's perception scene.
message ListWorldObjectResponse {
// Common response header
ResponseHeader header = 1;
// The currently perceived world objects.
repeated WorldObject world_objects = 2;
}
// The MutateWorldObject request message, which specifies the type of mutation and which object
// the mutation should be applied to.
message MutateWorldObjectRequest {
// Common request header
RequestHeader header = 1;
enum Action {
// Invalid action.
ACTION_UNKNOWN = 0;
// Add a new object.
ACTION_ADD = 1;
// Change an existing objected (ID'd by integer ID number). This is
// only allowed to change objects added by the API-user, and not
// objects detected by Spot's perception system.
ACTION_CHANGE = 2;
// Delete the object, ID'd by integer ID number. This is
// only allowed to change objects added by the API-user, and not
// objects detected by Spot's perception system.
ACTION_DELETE = 3;
}
message Mutation {
// The action (add, change, or delete) to be applied to a world object.
Action action = 1;
// World object to be mutated.
// If an object is being changed/deleted, then the world object id must match a world
// object id known by the service.
WorldObject object = 2;
}
// The mutation for this request.
Mutation mutation = 2;
}
// The MutateWorldObject response message, which includes the world object id for the object that
// the mutation was applied to if the request succeeds.
message MutateWorldObjectResponse {
// Common response header
ResponseHeader header = 1;
enum Status {
// Status of request is unknown. Check the status code of the response header.
STATUS_UNKNOWN = 0;
// Request was accepted; GetObjectListResponse must still be checked to verify the changes.
STATUS_OK = 1;
// The mutation object's ID is unknown such that the service could not recognize this
// object. This error applies to the CHANGE and DELETE actions, since it must identify the
// object by it's id number given by the service.
STATUS_INVALID_MUTATION_ID = 2;
// The mutation request is not allowed because it is attempting to change or delete an
// object detected by Spot's perception system.
STATUS_NO_PERMISSION = 3;
// The mutation request is not allowed because some aspect of the world object is invalid.
// For example, something could be defined in an unallowed reference frame.
STATUS_INVALID_WORLD_OBJECT = 4;
}
// Return status for the request.
Status status = 2;
// ID set by the world object service for the mutated object
int32 mutated_object_id = 4;
}
// A box or circle no-go region
message NoGoRegionProperties {
// Define the geometry of the region. Note that currently, these regions may only be defined in
// the Vision world frame, or Odometry world frame.
oneof region {
Box2WithFrame box = 1;
CircleWithFrame circle = 5;
}
// Nominally, setting a NoGoRegion will create both a body obstacle of the specified size, as
// well as foot obstacle with a slightly inflated size by about the width of the robot's foot,
// to prevent the robot from stepping right on the edge of the body obstacle. If this is not
// the desired behavior, change the parameters below:
// If set true, will NOT create a foot obstacle for this region.
bool disable_foot_obstacle_generation = 2;
// If set true, will NOT create a body obstacle for this region.
bool disable_body_obstacle_generation = 3;
// If set true, and a foot obstacle is being generated, will make the foot obstacle the exact
// size specified in the "region" field and NOT inflate by approx. robot foot width.
bool disable_foot_obstacle_inflation = 4;
}
// World object properties describing image coordinates associated with an object or scene.
message ImageProperties {
// Camera Source of such as "back", "frontleft", etc.
string camera_source = 1;
oneof image_data {
// Image coordinates of the corners of a polygon (pixels of x[row], y[col]) in either
// clockwise/counter clockwise order
Polygon coordinates = 2;
// A set of keypoints and their associated metadata.
KeypointSet keypoints = 4;
}
// Camera parameters.
ImageSource image_source = 5;
// Image that produced the data.
ImageCapture image_capture = 6;
// Frame name for the object described by image coordinates.
string frame_name_image_coordinates = 3;
}
// World object properties describing a dock
message DockProperties {
// Consistent id associated with a given dock.
uint32 dock_id = 1;
// Type of dock.
docking.DockType type = 2;
// The frame name for the location of dock origin. This will be included in the transform
// snapshot.
string frame_name_dock = 3;
// Availability if the dock can be used
bool unavailable = 4;
// The dock is an unconfirmed prior detection
bool from_prior = 5;
}
// World object properties describing a fiducial object.
message AprilTagProperties {
enum AprilTagPoseStatus {
STATUS_UNKNOWN = 0;
// No known issues with the pose estimate.
STATUS_OK = 1;
// The orientation of the tag is ambiguous.
STATUS_AMBIGUOUS = 2;
// The pose may be unreliable due to high reprojection error.
STATUS_HIGH_ERROR = 3;
}
// Consistent integer id associated with a given apriltag. April Tag detections will be from the
// tag family 36h11.
int32 tag_id = 1;
// Apriltag size in meters, where x is the row/width length and y is the
// height/col length of the tag
Vec2 dimensions = 2;
// The frame name for the raw version of this fiducial. This will be included in the transform
// snapshot.
string frame_name_fiducial = 3;
// Status of the pose estimation of the unfiltered fiducial frame.
AprilTagPoseStatus fiducial_pose_status = 8;
// The frame name for the filtered version of this fiducial. This will be included in the
// transform snapshot.
string frame_name_fiducial_filtered = 4;
// Status of the pose estimation of the filtered fiducial frame.
AprilTagPoseStatus fiducial_filtered_pose_status = 9;
// The frame name for the camera that detected this fiducial.
string frame_name_camera = 7;
// A 6 x 6 Covariance matrix representing the marginal uncertainty of the last detection.
// The rows/columns are:
// rx, ry, rz, tx, ty, tz
// which represent incremental rotation and translation along the x, y, and z axes of the
// given frame, respectively.
// This is computed using the Jacobian of the pose estimation algorithm.
SE3Covariance detection_covariance = 5;
// The frame that the detection covariance is expressed in.
string detection_covariance_reference_frame = 6;
}
message RayProperties {
// Ray, usually pointing from the camera to the object.
Ray ray = 1;
// Frame the ray is expressed with respect to.
string frame = 2;
}
message BoundingBoxProperties {
// An Oriented Bounding Box, with position and orientation at the frame provided in the
// transforms snapshot.
//
// The size of the box is expressed with respect to the frame.
Vec3 size_ewrt_frame = 1;
// Frame the size is expressed with respect to.
string frame = 2;
}
// The drawing and visualization information for a world object.
message DrawableProperties {
// RGBA values for color ranging from [0,255] for R/G/B, and [0,1] for A.
message Color {
// Red value ranging from [0,255].
int32 r = 1;
/// Green value ranging from [0,255].
int32 g = 2;
// Blue value ranging from [0,255].
int32 b = 3;
// Alpha (transparency) value ranging from [0,1].
double a = 4;
}
// Color of the object.
Color color = 1;
// Label to be drawn at the origin of the object.
string label = 2;
// Drawn objects in wireframe.
bool wireframe = 3;
// The object to draw, e.g. a Sphere.
oneof drawable {
DrawableFrame frame = 4; // A drawable frame (oneof drawable field).
DrawableSphere sphere = 5; // A drawable sphere (oneof drawable field).
DrawableBox box = 6; // A drawable box (oneof drawable field).
DrawableArrow arrow = 7; // A drawable arrow (oneof drawable field).
DrawableCapsule capsule = 8; // A drawable capsule (oneof drawable field).
DrawableCylinder cylinder = 9; // A drawable cylinder (oneof drawable field).
DrawableLineStrip linestrip = 10; // A drawable linestrip (oneof drawable field).
DrawablePoints points = 11; // A drawable set of points (oneof drawable field).
}
// The frame name for the drawable object. This will optionally be
// included in the frame tree snapshot.
string frame_name_drawable = 12;
}
message StaircaseProperties {
Staircase staircase = 1;
}
// Properties related to GPS measurements of our location with respect to the Earth.
message GpsProperties {
bosdyn.api.gps.Registration registration = 1;
}
// A coordinate frame drawing object, describing how large to render the arrows.
message DrawableFrame {
double arrow_length = 1;
double arrow_radius = 2;
}
// A sphere drawing object.
message DrawableSphere {
double radius = 1;
}
// A three dimensional box drawing object.
message DrawableBox {
Vec3 size = 1;
}
// A directed arrow drawing object.
message DrawableArrow {
Vec3 direction = 1;
double radius = 2;
}
// A oval-like capsule drawing object.
message DrawableCapsule {
Vec3 direction = 1;
double radius = 2;
}
// A cylinder drawing object.
message DrawableCylinder {
Vec3 direction = 1;
double radius = 2;
}
// A line strip drawing object.
message DrawableLineStrip {
Vec3 points = 1;
}
// A set of points drawing object.
message DrawablePoints {
repeated Vec3 points = 1;
}