forked from foxglove/schemas
-
Notifications
You must be signed in to change notification settings - Fork 0
/
schemas.ts
1368 lines (1313 loc) · 38.1 KB
/
schemas.ts
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
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
import { FoxgloveEnumSchema, FoxgloveMessageSchema } from "./types";
const Color: FoxgloveMessageSchema = {
type: "message",
name: "Color",
description: "A color in RGBA format",
fields: [
{
name: "r",
type: { type: "primitive", name: "float64" },
description: "Red value between 0 and 1",
},
{
name: "g",
type: { type: "primitive", name: "float64" },
description: "Green value between 0 and 1",
},
{
name: "b",
type: { type: "primitive", name: "float64" },
description: "Blue value between 0 and 1",
},
{
name: "a",
type: { type: "primitive", name: "float64" },
description: "Alpha value between 0 and 1",
},
],
};
const Vector2: FoxgloveMessageSchema = {
type: "message",
name: "Vector2",
description: "A vector in 2D space that represents a direction only",
fields: [
{
name: "x",
type: { type: "primitive", name: "float64" },
description: "x coordinate length",
},
{
name: "y",
type: { type: "primitive", name: "float64" },
description: "y coordinate length",
},
],
};
const Vector3: FoxgloveMessageSchema = {
type: "message",
name: "Vector3",
description: "A vector in 3D space that represents a direction only",
rosEquivalent: "geometry_msgs/Vector3",
fields: [
{
name: "x",
type: { type: "primitive", name: "float64" },
description: "x coordinate length",
},
{
name: "y",
type: { type: "primitive", name: "float64" },
description: "y coordinate length",
},
{
name: "z",
type: { type: "primitive", name: "float64" },
description: "z coordinate length",
},
],
};
const Point2: FoxgloveMessageSchema = {
type: "message",
name: "Point2",
description: "A point representing a position in 2D space",
fields: [
{
name: "x",
type: { type: "primitive", name: "float64" },
description: "x coordinate position",
},
{
name: "y",
type: { type: "primitive", name: "float64" },
description: "y coordinate position",
},
],
};
const Point3: FoxgloveMessageSchema = {
type: "message",
name: "Point3",
description: "A point representing a position in 3D space",
rosEquivalent: "geometry_msgs/Point",
fields: [
{
name: "x",
type: { type: "primitive", name: "float64" },
description: "x coordinate position",
},
{
name: "y",
type: { type: "primitive", name: "float64" },
description: "y coordinate position",
},
{
name: "z",
type: { type: "primitive", name: "float64" },
description: "z coordinate position",
},
],
};
const Quaternion: FoxgloveMessageSchema = {
type: "message",
name: "Quaternion",
description: "A [quaternion](https://eater.net/quaternions) representing a rotation in 3D space",
rosEquivalent: "geometry_msgs/Quaternion",
fields: [
{
name: "x",
type: { type: "primitive", name: "float64" },
description: "x value",
},
{
name: "y",
type: { type: "primitive", name: "float64" },
description: "y value",
},
{
name: "z",
type: { type: "primitive", name: "float64" },
description: "z value",
},
{
name: "w",
type: { type: "primitive", name: "float64" },
description: "w value",
},
],
};
const Pose: FoxgloveMessageSchema = {
type: "message",
name: "Pose",
description: "A position and orientation for an object or reference frame in 3D space",
rosEquivalent: "geometry_msgs/Pose",
fields: [
{
name: "position",
type: { type: "nested", schema: Vector3 },
description: "Point denoting position in 3D space",
},
{
name: "orientation",
type: { type: "nested", schema: Quaternion },
description: "Quaternion denoting orientation in 3D space",
},
],
};
const KeyValuePair: FoxgloveMessageSchema = {
type: "message",
name: "KeyValuePair",
description: "A key with its associated value",
fields: [
{
name: "key",
type: { type: "primitive", name: "string" },
description: "Key",
},
{
name: "value",
type: { type: "primitive", name: "string" },
description: "Value",
},
],
};
const SceneEntityDeletionType: FoxgloveEnumSchema = {
type: "enum",
name: "SceneEntityDeletionType",
protobufParentMessageName: "SceneEntityDeletion",
protobufEnumName: "Type",
description:
"An enumeration indicating which entities should match a SceneEntityDeletion command",
values: [
{
value: 0,
name: "MATCHING_ID",
description: "Delete the existing entity on the same topic that has the provided `id`",
},
{ value: 1, name: "ALL", description: "Delete all existing entities on the same topic" },
],
};
const SceneEntityDeletion: FoxgloveMessageSchema = {
type: "message",
name: "SceneEntityDeletion",
description: "Command to remove previously published entities",
fields: [
{
name: "timestamp",
type: { type: "primitive", name: "time" },
description:
"Timestamp of the deletion. Only matching entities earlier than this timestamp will be deleted.",
},
{
name: "type",
type: { type: "enum", enum: SceneEntityDeletionType },
description: "Type of deletion action to perform",
},
{
name: "id",
type: { type: "primitive", name: "string" },
description: "Identifier which must match if `type` is `MATCHING_ID`.",
},
],
};
const ArrowPrimitive: FoxgloveMessageSchema = {
type: "message",
name: "ArrowPrimitive",
description: "A primitive representing an arrow",
fields: [
{
name: "pose",
type: { type: "nested", schema: Pose },
description:
"Position of the arrow's tail and orientation of the arrow. Identity orientation means the arrow points in the +x direction.",
},
{
name: "shaft_length",
type: { type: "primitive", name: "float64" },
description: "Length of the arrow shaft",
},
{
name: "shaft_diameter",
type: { type: "primitive", name: "float64" },
description: "Diameter of the arrow shaft",
},
{
name: "head_length",
type: { type: "primitive", name: "float64" },
description: "Length of the arrow head",
},
{
name: "head_diameter",
type: { type: "primitive", name: "float64" },
description: "Diameter of the arrow head",
},
{
name: "color",
type: { type: "nested", schema: Color },
description: "Color of the arrow",
},
],
};
const CubePrimitive: FoxgloveMessageSchema = {
type: "message",
name: "CubePrimitive",
description: "A primitive representing a cube or rectangular prism",
fields: [
{
name: "pose",
type: { type: "nested", schema: Pose },
description: "Position of the center of the cube and orientation of the cube",
},
{
name: "size",
type: { type: "nested", schema: Vector3 },
description: "Size of the cube along each axis",
},
{
name: "color",
type: { type: "nested", schema: Color },
description: "Color of the arrow",
},
],
};
const SpherePrimitive: FoxgloveMessageSchema = {
type: "message",
name: "SpherePrimitive",
description: "A primitive representing a sphere or ellipsoid",
fields: [
{
name: "pose",
type: { type: "nested", schema: Pose },
description: "Position of the center of the sphere and orientation of the sphere",
},
{
name: "size",
type: { type: "nested", schema: Vector3 },
description: "Size (diameter) of the sphere along each axis",
},
{
name: "color",
type: { type: "nested", schema: Color },
description: "Color of the sphere",
},
],
};
const CylinderPrimitive: FoxgloveMessageSchema = {
type: "message",
name: "CylinderPrimitive",
description: "A primitive representing a cylinder, elliptic cylinder, or truncated cone",
fields: [
{
name: "pose",
type: { type: "nested", schema: Pose },
description:
"Position of the center of the cylinder and orientation of the cylinder. The flat face(s) are perpendicular to the z-axis.",
},
{
name: "size",
type: { type: "nested", schema: Vector3 },
description: "Size of the cylinder's bounding box",
},
{
name: "bottom_scale",
type: { type: "primitive", name: "float64" },
description:
"0-1, ratio of the diameter of the cylinder's bottom face (min z) to the bottom of the bounding box",
},
{
name: "top_scale",
type: { type: "primitive", name: "float64" },
description:
"0-1, ratio of the diameter of the cylinder's top face (max z) to the top of the bounding box",
},
{
name: "color",
type: { type: "nested", schema: Color },
description: "Color of the cylinder",
},
],
};
const LineType: FoxgloveEnumSchema = {
type: "enum",
name: "LineType",
protobufParentMessageName: "LinePrimitive",
protobufEnumName: "Type",
description: "An enumeration indicating how input points should be interpreted to create lines",
values: [
{ value: 0, name: "LINE_STRIP", description: "0-1, 1-2, ..., (n-1)-n" },
{ value: 1, name: "LINE_LOOP", description: "0-1, 1-2, ..., (n-1)-n, n-0" },
{ value: 2, name: "LINE_LIST", description: "0-1, 2-3, 4-5, ..." },
],
};
const LinePrimitive: FoxgloveMessageSchema = {
type: "message",
name: "LinePrimitive",
description: "A primitive representing a series of points connected by lines",
fields: [
{
name: "type",
type: { type: "enum", enum: LineType },
description: "Drawing primitive to use for lines",
},
{
name: "pose",
type: { type: "nested", schema: Pose },
description: "Origin of lines relative to reference frame",
},
{
name: "thickness",
type: { type: "primitive", name: "float64" },
description: "Line thickness",
},
{
name: "scale_invariant",
type: { type: "primitive", name: "boolean" },
description:
"Indicates whether `thickness` is a fixed size in screen pixels (true), or specified in world coordinates and scales with distance from the camera (false)",
},
{
name: "points",
type: { type: "nested", schema: Point3 },
array: true,
description: "Points along the line",
},
{
name: "color",
type: { type: "nested", schema: Color },
description:
"Solid color to use for the whole line. One of `color` or `colors` must be provided.",
},
{
name: "colors",
type: { type: "nested", schema: Color },
array: true,
description:
"Per-point colors (if specified, must have the same length as `points`). One of `color` or `colors` must be provided.",
},
{
name: "indices",
type: { type: "primitive", name: "uint32" },
array: true,
description:
"Indices into the `points` and `colors` attribute arrays, which can be used to avoid duplicating attribute data.\n\nIf omitted or empty, indexing will not be used. This default behavior is equivalent to specifying [0, 1, ..., N-1] for the indices (where N is the number of `points` provided).",
},
],
};
const TextPrimitive: FoxgloveMessageSchema = {
type: "message",
name: "TextPrimitive",
description: "A primitive representing a text label",
fields: [
{
name: "pose",
type: { type: "nested", schema: Pose },
description:
"Position of the center of the text box and orientation of the text. Identity orientation means the text is oriented in the xy-plane and flows from -x to +x.",
},
{
name: "billboard",
type: { type: "primitive", name: "boolean" },
description:
"Whether the text should respect `pose.orientation` (false) or always face the camera (true)",
},
{
name: "font_size",
type: { type: "primitive", name: "float64" },
description: "Font size (height of one line of text)",
},
{
name: "scale_invariant",
type: { type: "primitive", name: "boolean" },
description:
"Indicates whether `font_size` is a fixed size in screen pixels (true), or specified in world coordinates and scales with distance from the camera (false)",
},
{
name: "color",
type: { type: "nested", schema: Color },
description: "Color of the text",
},
{
name: "text",
type: { type: "primitive", name: "string" },
description: "Text",
},
],
};
const TriangleListPrimitive: FoxgloveMessageSchema = {
type: "message",
name: "TriangleListPrimitive",
description: "A primitive representing a set of triangles or a surface tiled by triangles",
fields: [
{
name: "pose",
type: { type: "nested", schema: Pose },
description: "Origin of triangles relative to reference frame",
},
{
name: "points",
type: { type: "nested", schema: Point3 },
array: true,
description:
"Vertices to use for triangles, interpreted as a list of triples (0-1-2, 3-4-5, ...)",
},
{
name: "color",
type: { type: "nested", schema: Color },
description:
"Solid color to use for the whole shape. One of `color` or `colors` must be provided.",
},
{
name: "colors",
type: { type: "nested", schema: Color },
array: true,
description:
"Per-vertex colors (if specified, must have the same length as `points`). One of `color` or `colors` must be provided.",
},
{
name: "indices",
type: { type: "primitive", name: "uint32" },
array: true,
description:
"Indices into the `points` and `colors` attribute arrays, which can be used to avoid duplicating attribute data.\n\nIf omitted or empty, indexing will not be used. This default behavior is equivalent to specifying [0, 1, ..., N-1] for the indices (where N is the number of `points` provided).",
},
],
};
const ModelPrimitive: FoxgloveMessageSchema = {
type: "message",
name: "ModelPrimitive",
description:
"A primitive representing a 3D model file loaded from an external URL or embedded data",
fields: [
{
name: "pose",
type: { type: "nested", schema: Pose },
description: "Origin of model relative to reference frame",
},
{
name: "scale",
type: { type: "nested", schema: Vector3 },
description: "Scale factor to apply to the model along each axis",
},
{
name: "color",
type: { type: "nested", schema: Color },
description: "Solid color to use for the whole model if `override_color` is true.",
},
{
name: "override_color",
type: { type: "primitive", name: "boolean" },
description:
"Whether to use the color specified in `color` instead of any materials embedded in the original model.",
},
{
name: "url",
type: { type: "primitive", name: "string" },
description: "URL pointing to model file. One of `url` or `data` should be provided.",
},
{
name: "media_type",
type: { type: "primitive", name: "string" },
description:
"[Media type](https://developer.mozilla.org/en-US/docs/Web/HTTP/Basics_of_HTTP/MIME_types) of embedded model (e.g. `model/gltf-binary`). Required if `data` is provided instead of `url`. Overrides the inferred media type if `url` is provided.",
},
{
name: "data",
type: { type: "primitive", name: "bytes" },
description:
"Embedded model. One of `url` or `data` should be provided. If `data` is provided, `media_type` must be set to indicate the type of the data.",
},
],
};
const SceneEntity: FoxgloveMessageSchema = {
type: "message",
name: "SceneEntity",
description:
"A visual element in a 3D scene. An entity may be composed of multiple primitives which all share the same frame of reference.",
fields: [
{
name: "timestamp",
type: { type: "primitive", name: "time" },
description: "Timestamp of the entity",
},
{
name: "frame_id",
type: { type: "primitive", name: "string" },
description: "Frame of reference",
},
{
name: "id",
type: { type: "primitive", name: "string" },
description:
"Identifier for the entity. A entity will replace any prior entity on the same topic with the same `id`.",
},
{
name: "lifetime",
type: { type: "primitive", name: "duration" },
description:
"Length of time (relative to `timestamp`) after which the entity should be automatically removed. Zero value indicates the entity should remain visible until it is replaced or deleted.",
},
{
name: "frame_locked",
type: { type: "primitive", name: "boolean" },
description:
"Whether the entity should keep its location in the fixed frame (false) or follow the frame specified in `frame_id` as it moves relative to the fixed frame (true)",
},
{
name: "metadata",
type: { type: "nested", schema: KeyValuePair },
array: true,
description:
"Additional user-provided metadata associated with the entity. Keys must be unique.",
},
{
name: "arrows",
type: { type: "nested", schema: ArrowPrimitive },
array: true,
description: "Arrow primitives",
},
{
name: "cubes",
type: { type: "nested", schema: CubePrimitive },
array: true,
description: "Cube primitives",
},
{
name: "spheres",
type: { type: "nested", schema: SpherePrimitive },
array: true,
description: "Sphere primitives",
},
{
name: "cylinders",
type: { type: "nested", schema: CylinderPrimitive },
array: true,
description: "Cylinder primitives",
},
{
name: "lines",
type: { type: "nested", schema: LinePrimitive },
array: true,
description: "Line primitives",
},
{
name: "triangles",
type: { type: "nested", schema: TriangleListPrimitive },
array: true,
description: "Triangle list primitives",
},
{
name: "texts",
type: { type: "nested", schema: TextPrimitive },
array: true,
description: "Text primitives",
},
{
name: "models",
type: { type: "nested", schema: ModelPrimitive },
array: true,
description: "Model primitives",
},
],
};
const SceneUpdate: FoxgloveMessageSchema = {
type: "message",
name: "SceneUpdate",
description: "An update to the entities displayed in a 3D scene",
fields: [
{
name: "deletions",
type: { type: "nested", schema: SceneEntityDeletion },
array: true,
description: "Scene entities to delete",
},
{
name: "entities",
type: { type: "nested", schema: SceneEntity },
array: true,
description: "Scene entities to add or replace",
},
],
};
const CameraCalibration: FoxgloveMessageSchema = {
type: "message",
name: "CameraCalibration",
description: "Camera calibration parameters",
fields: [
{
name: "timestamp",
type: { type: "primitive", name: "time" },
description: "Timestamp of calibration data",
},
{
name: "frame_id",
type: { type: "primitive", name: "string" },
description:
"Frame of reference for the camera. The origin of the frame is the optical center of the camera. +x points to the right in the image, +y points down, and +z points into the plane of the image.",
protobufFieldNumber: 9,
},
{
name: "width",
type: { type: "primitive", name: "uint32" },
description: "Image width",
},
{
name: "height",
type: { type: "primitive", name: "uint32" },
description: "Image height",
},
{
name: "distortion_model",
type: { type: "primitive", name: "string" },
description: "Name of distortion model",
},
{
name: "D",
type: { type: "primitive", name: "float64" },
description: "Distortion parameters",
array: true,
},
{
name: "K",
type: { type: "primitive", name: "float64" },
array: 9,
description: `Intrinsic camera matrix (3x3 row-major matrix)
A 3x3 row-major matrix for the raw (distorted) image.
Projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx, fy) and principal point (cx, cy).
\`\`\`
[fx 0 cx]
K = [ 0 fy cy]
[ 0 0 1]
\`\`\`
`,
},
{
name: "R",
type: { type: "primitive", name: "float64" },
array: 9,
description: `Rectification matrix (3x3 row-major matrix)
A rotation matrix aligning the camera coordinate system to the ideal stereo image plane so that epipolar lines in both stereo images are parallel.`,
},
{
name: "P",
type: { type: "primitive", name: "float64" },
array: 12,
description: `Projection/camera matrix (3x4 row-major matrix)
\`\`\`
[fx' 0 cx' Tx]
P = [ 0 fy' cy' Ty]
[ 0 0 1 0]
\`\`\`
By convention, this matrix specifies the intrinsic (camera) matrix of the processed (rectified) image. That is, the left 3x3 portion is the normal camera intrinsic matrix for the rectified image.
It projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx', fy') and principal point (cx', cy') - these may differ from the values in K.
For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will also have R = the identity and P[1:3,1:3] = K.
For a stereo pair, the fourth column [Tx Ty 0]' is related to the position of the optical center of the second camera in the first camera's frame. We assume Tz = 0 so both cameras are in the same stereo image plane. The first camera always has Tx = Ty = 0. For the right (second) camera of a horizontal stereo pair, Ty = 0 and Tx = -fx' * B, where B is the baseline between the cameras.
Given a 3D point [X Y Z]', the projection (x, y) of the point onto the rectified image is given by:
\`\`\`
[u v w]' = P * [X Y Z 1]'
x = u / w
y = v / w
\`\`\`
This holds for both images of a stereo pair.
`,
},
],
};
const CompressedImage: FoxgloveMessageSchema = {
type: "message",
name: "CompressedImage",
description: "A compressed image",
fields: [
{
name: "timestamp",
type: { type: "primitive", name: "time" },
description: "Timestamp of image",
},
{
name: "frame_id",
type: { type: "primitive", name: "string" },
description:
"Frame of reference for the image. The origin of the frame is the optical center of the camera. +x points to the right in the image, +y points down, and +z points into the plane of the image.",
protobufFieldNumber: 4,
},
{
name: "data",
type: { type: "primitive", name: "bytes" },
description: "Compressed image data",
},
{
name: "format",
type: { type: "primitive", name: "string" },
description: "Image format",
},
],
};
const RawImage: FoxgloveMessageSchema = {
type: "message",
name: "RawImage",
description: "A raw image",
fields: [
{
name: "timestamp",
type: { type: "primitive", name: "time" },
description: "Timestamp of image",
},
{
name: "frame_id",
type: { type: "primitive", name: "string" },
description:
"Frame of reference for the image. The origin of the frame is the optical center of the camera. +x points to the right in the image, +y points down, and +z points into the plane of the image.",
protobufFieldNumber: 7,
},
{
name: "width",
type: { type: "primitive", name: "uint32" },
description: "Image width",
},
{
name: "height",
type: { type: "primitive", name: "uint32" },
description: "Image height",
},
{
name: "encoding",
type: { type: "primitive", name: "string" },
description: "Encoding of the raw image data",
},
{
name: "step",
type: { type: "primitive", name: "uint32" },
description: "Byte length of a single row",
},
{
name: "data",
type: { type: "primitive", name: "bytes" },
description: "Raw image data",
},
],
};
const FrameTransform: FoxgloveMessageSchema = {
type: "message",
name: "FrameTransform",
description: "A transform between two reference frames in 3D space",
fields: [
{
name: "timestamp",
type: { type: "primitive", name: "time" },
description: "Timestamp of transform",
},
{
name: "parent_frame_id",
type: { type: "primitive", name: "string" },
description: "Name of the parent frame",
},
{
name: "child_frame_id",
type: { type: "primitive", name: "string" },
description: "Name of the child frame",
},
{
name: "translation",
type: { type: "nested", schema: Vector3 },
description: "Translation component of the transform",
},
{
name: "rotation",
type: { type: "nested", schema: Quaternion },
description: "Rotation component of the transform",
},
],
};
const PoseInFrame: FoxgloveMessageSchema = {
type: "message",
name: "PoseInFrame",
description: "A timestamped pose for an object or reference frame in 3D space",
fields: [
{
name: "timestamp",
type: { type: "primitive", name: "time" },
description: "Timestamp of pose",
},
{
name: "frame_id",
type: { type: "primitive", name: "string" },
description: "Frame of reference for pose position and orientation",
},
{
name: "pose",
type: { type: "nested", schema: Pose },
description: "Pose in 3D space",
},
],
};
const PosesInFrame: FoxgloveMessageSchema = {
type: "message",
name: "PosesInFrame",
description: "An array of timestamped poses for an object or reference frame in 3D space",
fields: [
{
name: "timestamp",
type: { type: "primitive", name: "time" },
description: "Timestamp of pose",
},
{
name: "frame_id",
type: { type: "primitive", name: "string" },
description: "Frame of reference for pose position and orientation",
},
{
name: "poses",
type: { type: "nested", schema: Pose },
description: "Poses in 3D space",
array: true,
},
],
};
const GeoJSON: FoxgloveMessageSchema = {
type: "message",
name: "GeoJSON",
description: "GeoJSON data for annotating maps",
fields: [
{
name: "geojson",
type: { type: "primitive", name: "string" },
description: "GeoJSON data encoded as a UTF-8 string",
},
],
};
const NumericType: FoxgloveEnumSchema = {
type: "enum",
name: "NumericType",
description: "Numeric type",
protobufParentMessageName: "PackedElementField",
protobufEnumName: "NumericType",
values: [
{ name: "UNKNOWN", value: 0 },
{ name: "UINT8", value: 1 },
{ name: "INT8", value: 2 },
{ name: "UINT16", value: 3 },
{ name: "INT16", value: 4 },
{ name: "UINT32", value: 5 },
{ name: "INT32", value: 6 },
{ name: "FLOAT32", value: 7 },
{ name: "FLOAT64", value: 8 },
],
};
const PackedElementField: FoxgloveMessageSchema = {
type: "message",
name: "PackedElementField",
description: "A field present within each element in a byte array of packed elements.",
fields: [
{
name: "name",
type: { type: "primitive", name: "string" },
description: "Name of the field",
},
{
name: "offset",
type: { type: "primitive", name: "uint32" },
description: "Byte offset from start of data buffer",
},
{
name: "type",
type: { type: "enum", enum: NumericType },
description: "Type of data in the field. Integers are stored using little-endian byte order.",
},
],
};
const Grid: FoxgloveMessageSchema = {
type: "message",
name: "Grid",
description: "A 2D grid of data",
fields: [
{
name: "timestamp",
type: { type: "primitive", name: "time" },
description: "Timestamp of grid",
},
{
name: "frame_id",
type: { type: "primitive", name: "string" },
description: "Frame of reference",
},
{
name: "pose",
type: { type: "nested", schema: Pose },
description:
"Origin of grid's corner relative to frame of reference; grid is positioned in the x-y plane relative to this origin",
},
{
name: "column_count",
type: { type: "primitive", name: "uint32" },
description: "Number of grid columns",
},
{
name: "cell_size",
type: { type: "nested", schema: Vector2 },
description: "Size of single grid cell along x and y axes, relative to `pose`",
},
{
name: "row_stride",
type: { type: "primitive", name: "uint32" },
description: "Number of bytes between rows in `data`",
},
{
name: "cell_stride",
type: { type: "primitive", name: "uint32" },
description: "Number of bytes between cells within a row in `data`",
},
{
name: "fields",