-
Notifications
You must be signed in to change notification settings - Fork 599
Expand file tree
/
Copy pathimage.proto
More file actions
357 lines (285 loc) · 13.3 KB
/
image.proto
File metadata and controls
357 lines (285 loc) · 13.3 KB
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
// 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 go_package = "bosdyn/api/image";
option java_outer_classname = "ImageProto";
import "bosdyn/api/header.proto";
import "bosdyn/api/geometry.proto";
import "bosdyn/api/service_customization.proto";
import "google/protobuf/duration.proto";
import "google/protobuf/timestamp.proto";
// Rectangular color/greyscale/depth images.
message Image {
enum Format {
// Unknown image format.
FORMAT_UNKNOWN = 0;
// Color/greyscale formats.
// JPEG format.
FORMAT_JPEG = 1;
// Uncompressed. Requires pixel_format.
FORMAT_RAW = 2;
// 1 byte run-length before each pixel value.
FORMAT_RLE = 3;
}
enum PixelFormat {
// Unspecified value -- should not be used.
PIXEL_FORMAT_UNKNOWN = 0;
// One byte per pixel.
PIXEL_FORMAT_GREYSCALE_U8 = 1;
// Three bytes per pixel.
PIXEL_FORMAT_RGB_U8 = 3;
// Four bytes per pixel.
PIXEL_FORMAT_RGBA_U8 = 4;
// Little-endian uint16 z-distance from camera (mm).
PIXEL_FORMAT_DEPTH_U16 = 5;
// Big-endian uint16
PIXEL_FORMAT_GREYSCALE_U16 = 6;
}
// Number of columns in the image (in pixels).
int32 cols = 2;
// Number of rows in the image (in pixels).
int32 rows = 3;
// Raw image data.
bytes data = 4;
// How the image is encoded.
Format format = 5;
// Pixel format of the image; this will be set even when the Format implies
// the pixel format.
PixelFormat pixel_format = 6;
}
// Sensor parameters associated with an image capture.
message CaptureParameters {
// The duration of exposure in microseconds.
google.protobuf.Duration exposure_duration = 1;
// Sensor gain in dB.
double gain = 2;
// Any other custom parameters used in the image capture.
DictParam custom_params = 3;
}
// Rectangular color/greyscale images.
message ImageCapture {
// The time at which the image data was acquired in the robot's time basis.
google.protobuf.Timestamp acquisition_time = 30;
// A tree-based collection of transformations, which will include the transformations to each
// image's sensor in addition to transformations to the common frames ("vision", "body",
// "odom"). All transforms within the snapshot are at the acquisition time of the image.
FrameTreeSnapshot transforms_snapshot = 31;
// The frame name for the image's sensor source. This will be included in the transform
// snapshot.
string frame_name_image_sensor = 5;
// Image data.
Image image = 3;
// Sensor parameters associated with this image capture.
CaptureParameters capture_params = 4;
// Previous fields in the protobuf that are now reserved.
reserved 1, 2;
}
// Proto for a description of an image source on the robot.
message ImageSource {
// The camera can be modeled as a pinhole camera described with a matrix.
// Camera Matrix can be constructed by the camera intrinsics:
// [[focal_length.x, skew.x, principal_point.x],
// [[ skew.y, focal_length.y, principal_point.y],
// [[ 0, 0, 1]]
message PinholeModel {
// Intrinsic parameters are in pixel space.
message CameraIntrinsics {
// The focal length of the camera.
Vec2 focal_length = 1;
// The optical center in sensor coordinates.
Vec2 principal_point = 2;
// The skew for the intrinsic matrix.
Vec2 skew = 3;
}
// The camera intrinsics are necessary for describing the pinhole camera matrix.
CameraIntrinsics intrinsics = 1;
}
// The 5 parameter Brown-Conrady or "radtan" model is used to correct radial and
// tangential distortions. Original paper:
// http://close-range.com/docs/Decentering_Distortion_of_Lenses_Brown_1966_may_444-462.pdf
// We use the opencv convention for naming the distortion coefficients: k1, k2, p1, p2, k3. Here
// k1, k2, and k3 are radial distortion terms. p1 and p2 are tangential terms.
message PinholeBrownConrady {
message PinholeBrownConradyIntrinsics {
// Pinhole intrinsics of the camera.
PinholeModel.CameraIntrinsics pinhole_intrinsics = 1;
// The Brown-Conrady distortion coefficients for the camera.
float k1 = 2;
float k2 = 3;
float p1 = 4;
float p2 = 5;
float k3 = 6;
}
// The camera intrinsics are necessary for describing the KB4 camera matrix.
PinholeBrownConradyIntrinsics intrinsics = 1;
}
// The Kannala-Brandt camera model, also called the fisheye camera model in OpenCV
// (https://docs.opencv.org/4.x/db/d58/group__calib3d__fisheye.html) and the equidistant
// distortion model (https://github.com/ethz-asl/kalibr/wiki/supported-models), fits cameras
// with fisheye lenses well. The projection and un-projection equations for this model can be
// found at: https://arxiv.org/pdf/1807.08957.pdf.
message KannalaBrandtModel {
message KannalaBrandtIntrinsics {
// Pinhole intrinsics of the camera.
PinholeModel.CameraIntrinsics pinhole_intrinsics = 1;
// The Kannala-Brandt distortion coefficients for the camera.
float k1 = 2;
float k2 = 3;
float k3 = 4;
float k4 = 5;
}
// The camera intrinsics are necessary for describing the KB4 camera matrix.
KannalaBrandtIntrinsics intrinsics = 1;
}
// The name of this image source used to get images.
string name = 2;
// Number of columns in the image (in pixels).
int32 cols = 4;
// Number of rows in the image (in pixels).
int32 rows = 5;
// For depth images, the pixel value that represents a depth of one meter.
// Depth in meters can be computed by dividing the raw pixel value by this scale factor.
double depth_scale = 6;
// Fields reserved for deprecated messages.
reserved 3, 7;
oneof camera_models {
// Rectilinear camera model.
PinholeModel pinhole = 8;
// The pinhole camera model with the 5 parameter brown Conrady distortion model.
PinholeBrownConrady pinhole_brown_conrady = 13;
// The Kannala-Brandt camera model for modeling fisheye lenses.
KannalaBrandtModel kannala_brandt = 14;
}
enum ImageType {
// Unspecified image type.
IMAGE_TYPE_UNKNOWN = 0;
// Color or greyscale intensity image.
IMAGE_TYPE_VISUAL = 1;
// Pixel values represent distances to objects/surfaces.
IMAGE_TYPE_DEPTH = 2;
};
// The kind of images returned by this image source.
ImageType image_type = 9;
// The pixel formats a specific image source supports.
repeated Image.PixelFormat pixel_formats = 10;
// The image formats a specific image source supports.
repeated Image.Format image_formats = 11;
// ImageRequest parameters unique to this source that do not match any of the above fields.
DictParam.Spec custom_params = 12;
}
// The ListImageSources request message for the robot image service.
message ListImageSourcesRequest {
// Common request header.
RequestHeader header = 1;
}
// The ListImageSources response message which contains all known image sources for the robot.
message ListImageSourcesResponse {
// Common response Header.
ResponseHeader header = 1;
// The set of ImageSources available from this service.
// May be empty if the service serves no cameras (e.g., if no cameras were found on startup).
repeated ImageSource image_sources = 2;
// A tree-based collection of transformations, which will include the transformations to each
// image sources sensors in addition to transformations to the common frames ("vision", "body",
// "odom"). All transforms within the snapshot are at the time of the request.
FrameTreeSnapshot transforms_snapshot = 3;
}
// The image request specifying the image source and data format desired.
message ImageRequest {
// The string name of the image source to get image data from.
string image_source_name = 1;
// Image quality: a number from 0 (worst) to 100 (highest).
// Note that jpeg quality 100 is still lossy.
double quality_percent = 2;
// Specify the desired image encoding (e.g. JPEG, RAW). If no format is specified (e.g.
// FORMAT_UNKNOWN), the image service will choose the best format for the data.
Image.Format image_format = 3;
// Optional specification of the desired image dimensions.
// If the original image is 1920x1080, a resize_ratio of (2/3) will return an image with size
// 1280x720 The range is clipped to [0.01, 1] while maintaining the original aspect ratio. For
// backwards compatibility, a value of 0 means no resizing. Note: this field is not supported by
// the robot body cameras image service (`image`).
double resize_ratio = 4;
// Specify the desired pixel format (e.g. GREYSCALE_U8, RGB_U8). If no format is specified
// (e.g. PIXEL_FORMAT_UNKNOWN), the image service will choose the best format for the data.
Image.PixelFormat pixel_format = 5;
// Specify a pixel format that will be used if the format specified in the pixel_format field is
// invalid. If multiple formats are specified the valid format with the lowest index will be
// preferred.
repeated Image.PixelFormat fallback_formats = 7;
// Parameters unique to the servicer that do not match any of the above fields.
// Whether or not these are valid may depend on the values of the above fields.
DictParam custom_params = 6;
}
// The GetImage request message which can send multiple different image source requests at once.
message GetImageRequest {
// Common request header.
RequestHeader header = 1;
// The different image requests for this rpc call.
repeated ImageRequest image_requests = 2;
}
// The image response for each request, that includes image data and image source information.
message ImageResponse {
// The image capture contains the image data and information about the state of the camera and
// robot at the time the image was collected.
ImageCapture shot = 1;
// The source describes general information about the camera source the image data was collected
// from.
ImageSource source = 2;
enum Status {
// UNKNOWN should never be used.
// An internal ImageService issue has happened if UNKNOWN is set.
// None of the other fields are filled out.
STATUS_UNKNOWN = 0;
// Call succeeded at filling out all the fields.
STATUS_OK = 1;
// Image source name in request is unknown. Other fields are not filled out.
STATUS_UNKNOWN_CAMERA = 2;
// Failed to fill out ImageSource. All the other fields are not filled out.
STATUS_SOURCE_DATA_ERROR = 3;
// There was a problem with the image data. Only the ImageSource is filled out.
STATUS_IMAGE_DATA_ERROR = 4;
// The requested image format is unsupported for the image-source named. The image data will
// not be filled out. Note, if an image request has "FORMAT_UNKNOWN", the service should
// choose the best format to provide the data in.
STATUS_UNSUPPORTED_IMAGE_FORMAT_REQUESTED = 5;
// The requested pixel format is unsupported for the image-source named. The image data will
// not be filled out. Note, if an image request has "PIXEL_FORMAT_UNKNOWN", the service
// should choose the best format to provide the data in.
STATUS_UNSUPPORTED_PIXEL_FORMAT_REQUESTED = 6;
// The requested ratio is out of bounds [0,1] or unsupported by the image service
STATUS_UNSUPPORTED_RESIZE_RATIO_REQUESTED = 7;
// One or more keys or values in custom_params are unsupported by the image service.
// See the custom_param_error for details.
STATUS_CUSTOM_PARAMS_ERROR = 8;
}
// Return status of the request.
Status status = 4;
// Previous fields in the protobuf that are now reserved.
reserved 3, 5;
// Filled out if status is STATUS_CUSTOM_PARAMS_ERROR.
CustomParamError custom_param_error = 6;
}
// This message is a subset of the ImageResponse message with only the information needed
// to pass captured images to other services.
message ImageCaptureAndSource {
// The image capture contains the image data and information about the state of the camera and
// robot at the time the image was collected.
ImageCapture shot = 1;
// The source describes general information about the camera source the image data was collected
// from.
ImageSource source = 2;
// Image service. If blank, it is assumed to be the robot's default image service.
string image_service = 3;
}
// The GetImage response message which includes image data for all requested sources.
message GetImageResponse {
// Common response header.
ResponseHeader header = 1;
// The ordering of these image responses is defined by the order of the ImageRequests.
repeated ImageResponse image_responses = 2;
}