-
Notifications
You must be signed in to change notification settings - Fork 0
/
osi_common.proto
1110 lines (1011 loc) · 32.8 KB
/
osi_common.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
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
syntax = "proto2";
option optimize_for = SPEED;
package osi3;
//
// \brief A cartesian 3D vector for positions, velocities or accelerations or
// its uncertainties.
//
// The coordinate system is defined as right-handed.
//
// Units are m for positions, m/s for velocities, and m/s^2 for
// accelerations.
//
message Vector3d
{
// The x-coordinate.
//
// Unit: m, m/s, or m/s^2
//
optional double x = 1;
// The y-coordinate.
//
// Unit: m, m/s, or m/s^2
//
optional double y = 2;
// The z-coordinate.
//
// Unit: m, m/s, or m/s^2
//
optional double z = 3;
}
//
// \brief A cartesian 2D vector for positions, velocities or accelerations or
// its uncertainties.
//
// Units are m for positions, m/s for velocities, and m/s^2 for
// accelerations.
//
message Vector2d
{
// The x-coordinate.
//
// Unit: m, m/s, or m/s^2
//
optional double x = 1;
// The y-coordinate.
//
// Unit: m, m/s, or m/s^2
//
optional double y = 2;
}
//
// \brief A timestamp.
//
// Names and types of fields are chosen in accordance to
// google/protobuf/timestamp.proto to allow a possible switch in the future.
// There is no definition of the zero point in time neither it is the Unix
// epoch. A simulation may start at the zero point in time but it is not
// mandatory.
//
message Timestamp
{
// The number of seconds since the start of e.g. the simulation / system /
// vehicle.
//
// Unit: s
//
// \rules
// is_greater_than_or_equal_to: 0
// \endrules
//
optional int64 seconds = 1;
// The number of nanoseconds since the start of the last second.
//
// Range: [0, 999.999.999]
//
// Unit: ns
//
// \rules
// is_greater_than_or_equal_to: 0
// is_less_than_or_equal_to: 999999999
// \endrules
//
optional uint32 nanos = 2;
}
//
// \brief The dimension of a 3D box, e.g. the size of a 3D bounding box or its
// uncertainties.
//
// \image html OSI_Dimension3D.svg
//
// The dimensions are positive. Uncertainties are negative or positive.
//
// Dimension is defined in the specified reference coordinate frame along the
// x-axis (=length), y-axis (=width) and z-axis (=height).
//
message Dimension3d
{
// The length of the box.
//
// Unit: m
//
// \rules
// is_greater_than_or_equal_to: 0
// \endrules
//
optional double length = 1;
// The width of the box.
//
// Unit: m
//
// \rules
// is_greater_than_or_equal_to: 0
// \endrules
//
optional double width = 2;
// The height of the box.
//
// Unit: m
//
// \rules
// is_greater_than_or_equal_to: 0
// \endrules
//
optional double height = 3;
}
//
// \brief A 3D orientation, orientation rate or orientation acceleration (i.e.
// derivatives) or its uncertainties denoted in euler angles.
//
// Units are rad for orientation, rad/s for rates, and rad/s^2 for
// accelerations
//
// The coordinate system is defined as right-handed.
// For the sense of each rotation, the right-hand rule applies.
//
// The rotations are to be performed \b yaw \b first (around the z-axis),
// \b pitch \b second (around the new y-axis) and \b roll \b third (around the
// new x-axis) to follow the definition according to [1] (Tait-Bryan / Euler
// convention z-y'-x''). The preferred angular range is [-pi, pi] for roll
// and yaw and [-pi/2, pi/2] for pitch.
//
// Roll/Pitch are 0 if the objects xy-plane is parallel to its parent's
// xy-plane. Yaw is 0 if the object's local x-axis is parallel to its parent's
// x-axis.
//
// \f$ Rotation_{yaw,pitch,roll} =
// Rotation_{yaw}*Rotation_{pitch}*Rotation_{roll} \f$
//
// \f$ vector_{global coord system} := Rotation_{yaw, pitch, roll} * vector_{local coord system} +local_{origin::position} \f$
//
// \attention This definition changed in OSI version 3.0.0. Previous OSI
// versions (V2.xx) had an other definition.
//
// \par Reference:
// [1] DIN Deutsches Institut fuer Normung e. V. (2013). <em>DIN ISO 8855 Strassenfahrzeuge - Fahrzeugdynamik und Fahrverhalten - Begriffe</em>. (DIN ISO 8855:2013-11). Berlin, Germany.
//
message Orientation3d
{
// The roll angle/rate/acceleration.
//
// Unit: rad, rad/s, or rad/s^2
//
optional double roll = 1;
// The pitch angle/rate/acceleration.
//
// Unit: rad, rad/s, or rad/s^2
//
optional double pitch = 2;
// The yaw angle/rate/acceleration.
//
// Unit: rad, rad/s, or rad/s^2
//
optional double yaw = 3;
}
//
// \brief A common identifier (ID), represented as an integer.
//
// Has to be unique among all simulated items at any given time. For ground
// truth, the identifier of an item (object, lane, sign, etc.) must remain
// stable over its lifetime. \c Identifier values may be only be reused if the
// available address space is exhausted and the specific values have not been in
// use for several time steps. Sensor specific tracking IDs have no restrictions
// and should behave according to the sensor specifications.
// Purely simulation technical IDs, like sensor IDs, are not required to be
// unique among all simulated items, but rather unique within the context of the
// given message type.
//
// The value MAX(uint64) = 2^(64) -1 =
// 0b1111111111111111111111111111111111111111111111111111111111111111 is
// reserved and indicates an invalid ID or error.
//
message Identifier
{
// The value of the identifier.
//
// \rules
// is_greater_than_or_equal_to: 0
// \endrules
//
optional uint64 value = 1;
}
// \brief References to external objects.
//
// The external reference is an optional recommendation to refer to objects defined outside of OSI.
// This could be other OpenX standards, 3rd-party standards or user-defined objects.
//
// \note ExternalReference is optional and can be left empty.
//
message ExternalReference
{
// The source of the external references.
//
// Defines the original source of an object as uniquely identifiable reference.
// In case of using \c GroundTruth::map_reference or
// \c GroundTruth::model_reference, the reference can be left empty.
// If not otherwise required, an URI is suggested. The syntax should follow
// \link https://tools.ietf.org/html/rfc3986 RFC 3986\endlink.
//
//
optional string reference = 1;
// The type of the external references.
//
// Mandatory value describing the type of the original source.
//
// For OpenX/ASAM standards it is specified as follows:
// - net.asam.opendrive
// - net.asam.openscenario
//
// For third-party standards and user-defined objects,
// reverse domain name notation with lower-case type field
// is recommended to guarantee unique and interoperable identification.
//
// \rules
// is_set
// \endrules
//
optional string type = 2;
// The external identifier reference value.
//
// The repeated string is chosen as a common description of the external
// identifier, because a variety of identifier types could be
// involved .
//
// For example, referencing a unique lane in OpenDRIVE requires the
// following identifiers:
// * RoadId: String
// * S-Value of LaneSection: Double
// * LaneId: Int
//
// \note The detailed description of the identifiers and how they are
// used for referencing external objects is given in the individual
// messages where the external identifier is used.
//
// \see EnvironmentalConditions::source_reference
// \see Lane::source_reference
// \see LaneBoundary::source_reference
// \see StationaryObject::source_reference
// \see MovingObject::source_reference
// \see RoadMarking::source_reference
// \see TrafficLight::source_reference
// \see TrafficSign::source_reference
//
repeated string identifier = 3;
}
//
// \brief Specifies the mounting position of a sensor.
//
// Details are specified in each instance where \c MountingPosition is used.
//
message MountingPosition
{
// Offset position relative to the specified reference coordinate system.
//
optional Vector3d position = 1;
// Orientation offset relative to the specified reference coordinate system.
//
// \f$ Origin_{sensor} :=
// Rotation_{yaw,pitch,roll}( \f$ \c #orientation \f$
// )*(Origin_{\text{reference coord system}}
// - \f$ \c #position \f$ )\f$
//
optional Orientation3d orientation = 2;
}
//
// \brief A spherical representation for a point or vector in 3D space.
//
// Used e.g., for low level representations of radar detections.
//
// Azimuth and elevation are defined as the rotations that would have to be
// applied to the local frame (e.g sensor frame definition in
// \c SensorDetectionHeader) to make its x-axis point towards the referenced
// point or to align it with the referenced vector. The rotations are to be
// performed \b azimuth \b first (around the z-axis) and \b elevation \b second
// (around the new y-axis) to follow the definition of \c Orientation3d. For the
// sense of each rotation, the right-hand rule applies.
//
// \f$ vector_{cartesian} :=
// Rotation( \f$ \c #elevation \f$ )*Rotation( \f$ \c #azimuth \f$ )*
// (Unit_{vector_x}* \f$ \c #distance \f$ ) \f$
//
message Spherical3d
{
// The radial distance.
//
// Unit: m
//
// \rules
// is_greater_than_or_equal_to: 0
// \endrules
//
optional double distance = 1;
// The azimuth (horizontal) angle.
//
// Unit: rad
//
optional double azimuth = 2;
// The elevation (vertical) angle.
//
// Unit: rad
//
optional double elevation = 3;
}
//
// \brief Assignment of an object to a logical lane
//
// An object is assigned to a logical lane if it overlaps the logical lane.
// Assignment happens even if the reference point is outside the lane, and only
// a part of the object overlaps (any object overlapping the lane more than 5cm
// has to be assigned to the lane).
//
// As an exception to this, \c TrafficSign and \c TrafficLight are assigned to
// a logical lane if they control traffic on that lane. For \c TrafficSign and
// \c TrafficLight , #s_position refers to the position where the sign or light
// is valid (e.g. where vehicles should stop in case of a red traffic light),
// not the physical position (where the sign or light is in the world).
// Typically, t_position and angle_to_lane do not have any meaning in this
// case, and will be 0.
//
message LogicalLaneAssignment
{
// ID of the LogicalLane the object is assigned to.
//
// \rules
// refers_to: LogicalLane
// \endrules
//
optional Identifier assigned_lane_id = 1;
// S position of the object reference point on the lane, in the ST
// coordinate system of the lane.
//
// #s_position might be outside [s_start,s_end] of the lane (and even
// outside [startS,endS] of the reference line) if the reference point is
// outside the lane, but the object overlaps the lane or a TrafficSign or
// TrafficLight is assigned to a lane.
//
optional double s_position = 2;
// T position of the object reference point on the lane, in the ST
// coordinate system of the lane.
//
optional double t_position = 3;
// Angle of the object relative to the lane.
// See the ReferenceLine description how the angle is calculated.
//
// Unit: rad
//
optional double angle_to_lane = 4;
}
// \brief A bounding box description.
//
// A bounding box representing a sub-section of its parent's overall
// dimension, either that of a \c BaseMoving or \c BaseStationary .
//
// The parent frame of the \c BoundingBox is identical to the parent frame
// of the \c MovingObject or \c StationaryObject it is associated to. For
// example, if the parent object coordinates are given relative to the
// global coordinate system, then the \c BoundingBox coordinates are also
// given relative to the global coordinate system.
//
// \note The overall bounding box of the object is still defined using the
// dimension, position and orientation of the \c BaseMoving or
// \c BaseStationary .
//
message BoundingBox
{
// The 3D dimensions of the bounding box.
//
optional Dimension3d dimension = 1;
// The 3D position of the bounding box. The position is the center
// of the bounding box and the pivot for the \c dimension and \c orientation.
//
// \note The position should be within the same coordinate frame as
// its parent, not relative to coordinate frame of the parent object.
// The position becomes global/absolute if the parent frame is inertial
// (all parent frames up to ground truth).
//
optional Vector3d position = 2;
// The 3D orientation of the bounding box.
//
// \note The orientation should be within the same coordinate frame as
// its parent, not relative to the coordinate frame of the parent object.
// The orientation becomes global/absolute if the parent frame is inertial
// (all parent frames up to ground truth).
//
optional Orientation3d orientation = 3;
// The type of object contained in the bounding box.
//
optional Type contained_object_type = 4;
// Opaque reference of an associated 3D model of the bounding box.
//
// \note It is implementation-specific how model_references are resolved to
// 3d models. This means the coordinate system, model origin, and model
// orientation are also implementation-specific.
//
optional string model_reference = 5;
// Definition of different types of object contained within the bounding box
//
enum Type
{
// Object of unknown type (must not be used in ground truth).
//
TYPE_UNKNOWN = 0;
// Any other type of object.
//
TYPE_OTHER = 1;
// The main structure of an object, e.g. a chassis of a vehicle,
// or the central structure of a building, a tree trunk, etc.
//
TYPE_BASE_STRUCTURE = 2;
// A protruding, integral part of an object, which is not
// temporarily attached, e.g. a tree crown, a light pole arm, or a
// parking house gate. The protruding structure is meant to be an
// additional part to a base structure.
//
TYPE_PROTRUDING_STRUCTURE = 3;
// Additional, temporarily attached cargo to an object.
//
TYPE_CARGO = 4;
// The door of an object.
//
// For vehicles, this includes driver and passenger doors, trunk
// and front hoods, and fuel or charging port covers.
//
TYPE_DOOR = 5;
// The side mirror of a vehicle.
//
// \note The side mirror is not included in the overall bounding box
// of the parent object.
//
TYPE_SIDE_MIRROR = 6;
}
}
//
// \brief The base attributes of a stationary object or entity.
//
// This includes the \c StationaryObject , \c TrafficSign ,
// \c TrafficLight , \c RoadMarking messages.
//
// \image html OSI_BaseStationary.svg
//
// All coordinates and orientations from ground truth objects are relative to
// the global ground truth frame (see image). (All coordinates and orientations
// from detected objects are relative to the host vehicle frame (see:
// \c Vehicle vehicle reference point).)
//
message BaseStationary
{
// The 3D dimensions of the stationary object (bounding box), e.g. a
// landmark.
//
// \note The \c #dimension must completely enclose the geometry of the
// \c BaseStationary .
//
optional Dimension3d dimension = 1;
// The reference point for position and orientation, i.e. the center (x,y,z)
// of the bounding box.
//
optional Vector3d position = 2;
// The relative orientation of the stationary object w.r.t. its parent
// frame, noted in the parent frame. The orientation becomes global/absolute
// if the parent frame is inertial (all parent frames up to ground truth).
//
// \f$ Origin_{\text{base stationary entity}} :=
// Rotation_{yaw,pitch,roll}( \f$ \c #orientation \f$ )*
// (Origin_{\text{parent coord system}} -
// \f$ \c #position \f$ )\f$
//
// \note There may be some constraints how to align the orientation w.r.t.
// to some stationary object's or entity's definition.
//
optional Orientation3d orientation = 3;
// Usage as ground truth:
// The two dimensional (flat) contour of the object. This is an extension of
// the concept of a bounding box as defined by \c Dimension3d. The contour
// is the projection of the object's outline onto the z-plane in the object
// frame (independent of its current position and orientation). The height
// is the same as the height of the bounding box.
//
// Usage as sensor data:
// The polygon describes the visible part of the object's contour.
//
// General definitions:
// The polygon is defined in the local object frame: x pointing forward and
// y to the left.
// The origin is the center of the bounding box.
// As ground truth, the polygon is closed by connecting the last with the
// first point. Therefore these two points must be different. The polygon
// must consist of at least three points.
// As sensor data, however, the polygon is open.
// The polygon is defined counter-clockwise.
//
repeated Vector2d base_polygon = 4;
// Sub-divisions of the overall bounding box of the \c BaseStationary object.
//
// The bounding box sections can include separate parts on partially-opaque
// objects such as trees with a distinction between trunk and crown.
//
// \note The bounding box sub-divisions can extend beyond the overall
// bounding box, however no actual geometry must reside outside of the
// overall bounding box.
//
// \note If any sub-divisions are provided, then they must cover all
// occupied space of the overall bounding box. In other words, a consumer
// of this data is guaranteed that any part of the overall bounding box
// that is not covered by any sub-division is free of physical objects,
// and thus no collisions can occur there.
//
repeated BoundingBox bounding_box_section = 5;
}
//
// \brief The base attributes of an object that is moving.
//
// This includes the \c MovingObject messages.
//
// \image html OSI_BaseMoving.svg
//
// \image html OSI_BaseMoving_Top.svg
//
// E.g. a vehicle is a base moving object.
//
// All coordinates and orientations from ground truth objects are relative to
// the global ground truth frame. All coordinates and orientations
// from detected objects are relative to the host vehicle frame
// (see: \c MovingObject vehicle reference point).
//
message BaseMoving
{
// The 3D dimension of the moving object (its bounding box).
//
// \note The \c #dimension must completely enclose the geometry of the
// \c BaseMoving with the exception of the side mirrors for vehicles.
//
// \note The bounding box does NOT include side mirrors for vehicles.
//
optional Dimension3d dimension = 1;
// The reference point for position and orientation: the center (x,y,z) of
// the bounding box.
//
optional Vector3d position = 2;
// The relative orientation of the moving object w.r.t. its parent frame,
// noted in the parent frame. The orientation becomes global/absolute if
// the parent frame is inertial (all parent frames up to ground truth).
//
// \f$ Origin_{\text{base moving entity}} :=
// Rotation_{yaw,pitch,roll}( \f$ \c #orientation \f$ )*
// (Origin_{\text{parent coord system}} -
// \f$ \c #position \f$ ) \f$
//
// \note There may be some constraints how to align the orientation w.r.t.
// to some stationary object's or entity's definition.
//
optional Orientation3d orientation = 3;
// The relative velocity of the moving object w.r.t. the parent frame,
// noted in the parent frame. The velocity becomes global/absolute if
// the parent frame does is inertial (all parent frames up to ground truth).
//
// \c #position \f$ (t) := \f$ \c #position \f$ (t-dt)+ \f$ \c #velocity \f$
// *dt \f$
//
optional Vector3d velocity = 4;
// The relative acceleration of the moving object w.r.t. its parent frame,
// noted in the parent frame. The acceleration becomes global/absolute if
// the parent frame is inertial (all parent frames up to ground truth).
//
// \c #position \f$ (t) := \f$ \c #position \f$ (t-dt)+ \f$ \c #velocity \f$
// *dt+ \f$ \c #acceleration \f$ /2*dt^2\f$
//
// \c #velocity \f$ (t) := \f$ \c #velocity \f$ (t-dt)+ \f$ \c #acceleration
// \f$ *dt \f$
//
optional Vector3d acceleration = 5;
// The relative orientation rate of the moving object w.r.t. its parent
// frame and parent orientation rate in the center point of the bounding box
// (origin of the bounding box frame), noted in the parent frame.
// The orientation becomes global/absolute if the parent frame is inertial
// (all parent frames up to ground truth).
//
// \c #orientation \f$ .yaw(t) := \f$ \c #orientation_rate \f$ .yaw(t) * dt
// + \f$ \c #orientation \f$ .yaw(t-dt) \f$
//
// \c #orientation \f$ .pitch(t) := \f$ \c #orientation_rate \f$ .pitch(t) *
// dt + \f$ \c #orientation \f$ .pitch(t-dt) \f$
//
// \c #orientation \f$ .roll(t) := \f$ \c #orientation_rate \f$ .roll(t) *
// dt + \f$ \c #orientation \f$ .roll(t-dt)\f$
//
optional Orientation3d orientation_rate = 6;
// The relative orientation acceleration of the moving object w.r.t. its
// parent frame and parent orientation acceleration in the center point of
// the bounding box (origin of the bounding box frame), noted in the parent
// frame. The orientation becomes global/absolute if the parent frame is
// inertial (all parent frames up to ground truth).
//
// \c #orientation_rate \f$ .yaw(t) := \f$ \c #orientation_acceleration \f$
// .yaw(t) * dt + \f$ \c #orientation_rate \f$ .yaw(t-dt) \f$
//
// \c #orientation_rate \f$ .pitch(t) := \f$ \c #orientation_acceleration
// \f$ .pitch(t) * dt
// + \f$ \c #orientation_rate \f$ .pitch(t-dt) \f$
//
// \c #orientation_rate \f$ .roll(t) := \f$ \c #orientation_acceleration \f$
// .roll(t) * dt +
// \f$ \c #orientation_rate \f$ .roll(t-dt) \f$
//
optional Orientation3d orientation_acceleration = 8;
// Usage as ground truth:
// The two dimensional (flat) contour of the object. This is an extension of
// the concept of a bounding box as defined by \c Dimension3d. The contour
// is the projection of the object's outline onto the z-plane in the object
// frame (independent of its current position and orientation). The height
// is the same as the height of the bounding box.
//
// Usage as sensor data:
// The polygon describes the visible part of the object's contour.
//
// General definitions:
// The polygon is defined in the local object frame: x pointing forward and
// y to the left. The origin is the center of the bounding box.
// As ground truth, the polygon is closed by connecting the last with the
// first point. Therefore these two points must be different. The polygon
// must consist of at least three points. As sensor data, however, the
// polygon is open.
// The polygon is defined counter-clockwise.
//
repeated Vector2d base_polygon = 7;
// Sub-divisions of the overall bounding box of the \c BaseMoving object.
//
// The bounding box sections can include side mirrors, cargo, etc. for
// vehicles, as well as body-part sections for pedestrians. Note that for
// more precise pedestrian information \c PedestrianAttributes can be used.
//
// \note The bounding box sub-divisions can extend beyond the overall
// bounding box, however no actual geometry must reside outside of the
// overall bounding box, with the specific exception of the side mirrors.
//
// \note If any sub-divisions are provided, then they must cover all
// occupied space of the overall bounding box. In other words, a consumer
// of this data is guaranteed that any part of the overall bounding box
// that is not covered by any sub-division is free of physical objects,
// and thus no collisions can occur there.
//
repeated BoundingBox bounding_box_section = 9;
}
//
// \brief The StatePoint definition
//
// A reference to a time and pose. Typically used in a repeated field to define
// a trajectory.
//
// \note The StatePoint definition does not define mandatory fields.
// The context defines how and what fields are used. For example, in some cases
// only the pose variables are relevant and the timestamp is ignored.
//
message StatePoint
{
// The timestamp of a StatePoint.
//
// \note Zero time does not need to coincide with the UNIX epoch.
//
optional Timestamp timestamp = 1;
// Position in the global coordinate system.
//
// \note Remark: The definition of the reference point follows the
// specification of the \c BaseMoving message, if not specified otherwise
// in the message the StatePoint is used in.
//
optional Vector3d position = 2;
// Orientation in the global coordinate system.
//
optional Orientation3d orientation = 3;
}
//
// \brief Detailed WavelengthRange message.
//
// Defines the start (minimum) and the end (maximum) values of the wavelength.
// Additionally, the number of samples within this range is defined in this message.
//
message WavelengthData
{
// The start, or the minimum wavelength value.
//
// Unit: m
//
optional double start = 1;
// The end, or the maximum wavelength value.
//
// Unit: m
//
optional double end = 2;
// Number of samples to be considered within the defined wavelength range.
// The number of samples includes the start and the end values that are defined in this message, starting from the "start" value.
// \note This defines the number of wavelengths to be computed during simulation, not to be confused with samples_per_pixel.
//
optional double samples_number = 3;
}
//
// \brief Definition of a spatial signal strength distribution
// for an emitting / transmitting / receiving entity
// with a horizontal and a vertical angle
// and the corresponding signal strength in dBm (decibels per milliwatt).
//
message SpatialSignalStrength
{
// Horizontal angle (azimuth) of emission / transmission / reception
// in the entity's coordinate system.
//
// Unit: rad
//
optional double horizontal_angle = 1;
// Vertical angle (elevation) of emission / transmission / reception
// in the entity's coordinate system.
//
// Unit: rad
//
optional double vertical_angle = 2;
// Emitted / transmitted /received signal strength
// of the emitting / transmitting / receiving entity
// at the previously defined horizontal and
// vertical angle for one specific wavelength.
// The value for the signal strength
// is given in dBm (decibels per milliwatt).
//
// Unit: dBm
//
optional double signal_strength = 3;
}
//
// \brief The description of a color within available color spaces.
//
// ColorDescription represents the visual, non-semantic appearance of an object, structure or feature within various available color spaces.
//
// Depending on the context, this may define the color of an object or structure a priori (e.g. GroundTruth objects)
// or describe a perceived color (e.g. CameraDetections).
//
message ColorDescription
{
// Grayscale color model
//
optional ColorGrey grey = 1;
// RGB (Red, Green, Blue) color model
//
optional ColorRGB rgb = 2;
// RGBIR (Red, Green, Blue, Infrared) color model
//
optional ColorRGBIR rgbir = 3;
// HSV (Hue, Saturation, Value) color model
//
optional ColorHSV hsv = 4;
// LUV (Luminance, U-coordinate, V-coordinate) color model
//
optional ColorLUV luv = 5;
// CMYK (Cyan, Magenta, Yellow, Key) color model
//
optional ColorCMYK cmyk = 6;
}
//
// \brief Grayscale color model
//
// ColorGrey defines a grayscale.
//
message ColorGrey
{
// Definition of a grayscale
//
// Range: [0,1]
//
optional double grey = 1;
}
//
// \brief RGB color model
//
// ColorRGB provides values for red, green and blue.
//
message ColorRGB
{
// Red ratio
//
// Range: [0,1]
//
optional double red = 1;
// Green ratio
//
// Range: [0,1]
//
optional double green = 2;
// Blue ratio
//
// Range: [0,1]
//
optional double blue = 3;
}
//
// \brief RGBIR color model
//
// ColorRGBIR provides values for red, green, blue and infrared.
//
message ColorRGBIR
{
// Red ratio
//
// Range: [0,1]
//
optional double red = 1;
// Green ratio
//
// Range: [0,1]
//
optional double green = 2;
// Blue ratio
//
// Range: [0,1]
//
optional double blue = 3;
// Infrared
//
// Range: [0,1]
//
optional double infrared = 4;
}
//
// \brief HSV color model
//
// ColorHSV provides values for hue, saturation and value/brightness.
//
message ColorHSV
{
// Hue
//
// Unit: deg
// Range: [0,360[
//
optional double hue = 1;
// Saturation
//
// Range: [0,1]
//
optional double saturation = 2;
// Value
//
// Range: [0,1]
//
optional double value = 3;
}
//
// \brief LUV color model
//
// ColorLUV provides values for luminance, U- and V-coordinate.
//
message ColorLUV
{
// Luminance
//
// Range: [0,1]
//
optional double luminance = 1;
// U-coordinate
//
// Range: [0,1]
//
optional double u = 2;
// V-Coordinate
//
// Range: [0,1]
//
optional double v = 3;
}
//
// \brief CMYK colors model
//
// ColorCMYK provides values for cyan, magenta, yellow and key/black.
//
message ColorCMYK
{
// Cyan ratio
//
// Range: [0,1]
//
optional double cyan = 1;
// Magenta ratio
//
// Range: [0,1]
//
optional double magenta = 2;
// Yellow ratio
//
// Range: [0,1]
//
optional double yellow = 3;
// Black ratio
//
// Range: [0,1]
//
optional double key = 4;
}