OpenRTM-aist IDL  1.2
ExtendedDataTypes.idl
Go to the documentation of this file.
1 // -*- IDL -*-
17 #ifndef ExtendedDataTypes_idl
18 #define ExtendedDataTypes_idl
19 
20 #include "BasicDataType.idl"
21 
22 module RTC {
28  struct RGBColour
29  {
30  double r;
31  double g;
32  double b;
33  };
34 
35  //------------------------------------------------------------
36  // 2D data types
37  //------------------------------------------------------------
38 
43  struct Point2D
44  {
46  double x;
48  double y;
49  };
50 
55  struct Vector2D
56  {
58  double x;
60  double y;
61  };
62 
67  struct Pose2D
68  {
72  double heading;
73  };
74 
79  struct Velocity2D
80  {
82  double vx;
84  double vy;
86  double va;
87  };
88 
94  {
96  double ax;
98  double ay;
99  };
100 
105  struct PoseVel2D
106  {
109  };
110 
115  struct Size2D
116  {
118  double l;
120  double w;
121  };
122 
127  struct Geometry2D
128  {
134  };
135 
141  {
143  double xx;
145  double xy;
147  double xt;
149  double yy;
151  double yt;
153  double tt;
154  };
155 
161  {
163  double xx;
165  double xy;
167  double yy;
168  };
169 
174  struct Carlike
175  {
177  double speed;
180  };
181 
187  {
189  double speed;
191  double heading;
192  };
193 
194  //------------------------------------------------------------
195  // 3D data types
196  //------------------------------------------------------------
197 
202  struct Point3D
203  {
205  double x;
207  double y;
209  double z;
210  };
211 
216  struct Vector3D
217  {
219  double x;
221  double y;
223  double z;
224  };
225 
231  {
233  double r;
235  double p;
237  double y;
238  };
239 
244  struct Pose3D
245  {
250  };
251 
256  struct Velocity3D
257  {
259  double vx;
261  double vy;
263  double vz;
265  double vr;
267  double vp;
269  double va;
270  };
271 
277  {
279  double avx;
281  double avy;
283  double avz;
284  };
285 
291  {
293  double ax;
295  double ay;
297  double az;
298  };
299 
305  {
307  double aax;
309  double aay;
311  double aaz;
312  };
313 
318  struct PoseVel3D
319  {
322  };
323 
328  struct Size3D
329  {
331  double l;
333  double w;
335  double h;
336  };
337 
342  struct Geometry3D
343  {
349  };
350 
356  {
358  double xx;
360  double xy;
362  double xz;
364  double xr;
366  double xp;
368  double xa;
370  double yy;
372  double yz;
374  double yr;
376  double yp;
378  double ya;
380  double zz;
382  double zr;
384  double zp;
386  double za;
388  double rr;
390  double rp;
392  double ra;
394  double pp;
396  double pa;
398  double aa;
399  };
400 
406  {
408  double speed;
411  };
412 
417  struct OAP
418  {
422  };
423 
424  //------------------------------------------------------------
425  // Timed data types
426  //------------------------------------------------------------
427 
433  {
436  };
437 
443  {
446  };
447 
453  {
456  };
457 
462  struct TimedPose2D
463  {
466  };
467 
473  {
476  };
477 
483  {
486  };
487 
493  {
496  };
497 
502  struct TimedSize2D
503  {
506  };
507 
513  {
516  };
517 
523  {
526  };
527 
533  {
536  };
537 
543  {
546  };
547 
553  {
556  };
557 
563  {
566  };
567 
573  {
576  };
577 
583  {
586  };
587 
592  struct TimedPose3D
593  {
596  };
597 
603  {
606  };
607 
613  {
616  };
617 
623  {
626  };
627 
633  {
636  };
637 
643  {
646  };
647 
652  struct TimedSize3D
653  {
656  };
657 
663  {
666  };
667 
673  {
676  };
677 
683  {
686  };
687 
692  struct TimedOAP
693  {
696  };
697 
702  struct Quaternion
703  {
704  double x;
705  double y;
706  double z;
707  double w;
708  };
709 
715  {
718  };
719 };
720 
721 #endif // ExtendedDataTypes_idl
double ra
(3, 5) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:392
double r
Definition: ExtendedDataTypes.idl:30
Pose3D pose
Definition: ExtendedDataTypes.idl:320
Pose and velocity in 3D cartesian space.
Definition: ExtendedDataTypes.idl:318
double x
X value in metres.
Definition: ExtendedDataTypes.idl:58
Time tm
Definition: ExtendedDataTypes.idl:494
double vx
Velocity along the x axis in metres per second.
Definition: ExtendedDataTypes.idl:259
Orientation3D orientation
3D orientation.
Definition: ExtendedDataTypes.idl:249
Data type for Quaternion.
Definition: ExtendedDataTypes.idl:702
Time tm
Definition: ExtendedDataTypes.idl:564
Time-stamped version of AngularVelocity3D.
Definition: ExtendedDataTypes.idl:612
Time-stamped version of PoseVel3D.
Definition: ExtendedDataTypes.idl:642
double vp
Pitch velocity in radians per second.
Definition: ExtendedDataTypes.idl:267
Definition: BasicDataType.idl:22
double avx
Velocity around the x axis, in radians per second.
Definition: ExtendedDataTypes.idl:279
Size in 3D cartesian space.
Definition: ExtendedDataTypes.idl:328
Time tm
Definition: ExtendedDataTypes.idl:534
double yy
(1, 1) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:370
AngularVelocity3D data
Definition: ExtendedDataTypes.idl:615
Time tm
Definition: ExtendedDataTypes.idl:434
Orientation, approach and position vectors.
Definition: ExtendedDataTypes.idl:417
Point in 2D cartesian space.
Definition: ExtendedDataTypes.idl:43
Covariance matrix for a 3D pose.
Definition: ExtendedDataTypes.idl:355
AngularAcceleration3D data
Definition: ExtendedDataTypes.idl:635
double vy
Velocity along the y axis in metres per second.
Definition: ExtendedDataTypes.idl:84
Time-stamped version of Pose3D.
Definition: ExtendedDataTypes.idl:592
Size2D data
Definition: ExtendedDataTypes.idl:505
OAP data
Definition: ExtendedDataTypes.idl:695
double zp
(2, 4) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:384
double yp
(1, 4) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:376
Covariance2D data
Definition: ExtendedDataTypes.idl:525
Orientation in 3D cartesian space.
Definition: ExtendedDataTypes.idl:230
double l
Length in metres.
Definition: ExtendedDataTypes.idl:118
double avy
Velocity around the y axis, in radians per second.
Definition: ExtendedDataTypes.idl:281
Time tm
Definition: ExtendedDataTypes.idl:694
PointCovariance2D data
Definition: ExtendedDataTypes.idl:535
double xp
(0, 4) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:366
Time tm
Definition: ExtendedDataTypes.idl:634
Covariance3D data
Definition: ExtendedDataTypes.idl:675
Time tm
Definition: ExtendedDataTypes.idl:444
Time-stamped version of SpeedHeading3D.
Definition: ExtendedDataTypes.idl:682
Time-stamped version of Size3D.
Definition: ExtendedDataTypes.idl:652
double w
Definition: ExtendedDataTypes.idl:707
double vy
Velocity along the y axis in metres per second.
Definition: ExtendedDataTypes.idl:261
double h
Height in metres.
Definition: ExtendedDataTypes.idl:335
Time-stamped version of Geometry3D.
Definition: ExtendedDataTypes.idl:662
Time-stamped version of AngularAcceleration3D.
Definition: ExtendedDataTypes.idl:632
Time tm
Definition: ExtendedDataTypes.idl:644
Time tm
Definition: ExtendedDataTypes.idl:464
double xz
(0, 2) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:362
double x
Definition: ExtendedDataTypes.idl:704
Vector3D data
Definition: ExtendedDataTypes.idl:575
double rr
(3, 3) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:388
Time tm
Definition: ExtendedDataTypes.idl:504
Time-stamped version of Acceleration3D.
Definition: ExtendedDataTypes.idl:622
Time-stamped version of Velocity2D.
Definition: ExtendedDataTypes.idl:472
double b
Definition: ExtendedDataTypes.idl:32
double speed
Speed in metres per second.
Definition: ExtendedDataTypes.idl:189
Velocities in 3D cartesian space.
Definition: ExtendedDataTypes.idl:256
Pose in 2D cartesian space.
Definition: ExtendedDataTypes.idl:67
double w
Width in metres.
Definition: ExtendedDataTypes.idl:333
Size2D size
Size of the device, taken with the origin at its base point.
Definition: ExtendedDataTypes.idl:133
double ya
(1, 5) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:378
double xy
(0, 1) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:145
Control specification for a robot capable of moving in a given direction in 2D space.
Definition: ExtendedDataTypes.idl:186
double pa
(4, 5) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:396
Time tm
Definition: ExtendedDataTypes.idl:604
Geometry information for a device in 2D cartesian space.
Definition: ExtendedDataTypes.idl:127
Acceleration2D data
Definition: ExtendedDataTypes.idl:485
Point2D position
2D position.
Definition: ExtendedDataTypes.idl:70
Pose2D pose
Definition: ExtendedDataTypes.idl:107
double zr
(2, 3) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:382
Vector2D data
Definition: ExtendedDataTypes.idl:455
Time-stamped version of Point2D.
Definition: ExtendedDataTypes.idl:442
Time-stamped version of Orientation3D.
Definition: ExtendedDataTypes.idl:582
Time tm
Definition: ExtendedDataTypes.idl:544
Timed version data type for Quaternion.
Definition: ExtendedDataTypes.idl:714
Time tm
Definition: ExtendedDataTypes.idl:584
Time-stamped version of Carlike.
Definition: ExtendedDataTypes.idl:542
double xx
(0, 0) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:358
Time-stamped version of RGBColour.
Definition: ExtendedDataTypes.idl:432
Vector in 3D cartesian space.
Definition: ExtendedDataTypes.idl:216
Vector3D orientation
Definition: ExtendedDataTypes.idl:419
double z
Z coordinate in metres.
Definition: ExtendedDataTypes.idl:209
Covariance matrix for a 2D point.
Definition: ExtendedDataTypes.idl:160
Size3D data
Definition: ExtendedDataTypes.idl:655
double rp
(3, 4) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:390
double xa
(0, 5) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:368
double x
X coordinate in metres.
Definition: ExtendedDataTypes.idl:205
Time tm
Definition: ExtendedDataTypes.idl:614
double w
Width in metres.
Definition: ExtendedDataTypes.idl:120
double y
Y value in metres.
Definition: ExtendedDataTypes.idl:60
PoseVel3D data
Definition: ExtendedDataTypes.idl:645
Orientation3D data
Definition: ExtendedDataTypes.idl:585
Point2D data
Definition: ExtendedDataTypes.idl:445
double yt
(1, 2) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:151
double xx
(0, 0) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:143
Time tm
Definition: ExtendedDataTypes.idl:574
Control specification for a car-like robot.
Definition: ExtendedDataTypes.idl:174
Time-stamped version of Covariance2D.
Definition: ExtendedDataTypes.idl:522
double az
Acceleration along the z axis, in metres per second per second.
Definition: ExtendedDataTypes.idl:297
Definition: BasicDataType.idl:26
Time tm
Definition: ExtendedDataTypes.idl:554
double yz
(1, 2) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:372
double xx
(0, 0) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:163
Pose and velocity in 2D cartesian space.
Definition: ExtendedDataTypes.idl:105
double ax
Acceleration along the x axis, in metres per second per second.
Definition: ExtendedDataTypes.idl:293
SpeedHeading2D data
Definition: ExtendedDataTypes.idl:555
double yr
(1, 3) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:374
Time tm
Definition: ExtendedDataTypes.idl:474
double tt
(2, 2) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:153
Time-stamped version of Vector2D.
Definition: ExtendedDataTypes.idl:452
double aay
Acceleration around the y axis, in radians per second per second.
Definition: ExtendedDataTypes.idl:309
double vr
Roll velocity in radians per second.
Definition: ExtendedDataTypes.idl:265
Accelerations in 3D cartesian space.
Definition: ExtendedDataTypes.idl:290
SpeedHeading3D data
Definition: ExtendedDataTypes.idl:685
Size in 2D cartesian space.
Definition: ExtendedDataTypes.idl:115
double x
X coordinate in metres.
Definition: ExtendedDataTypes.idl:46
double g
Definition: ExtendedDataTypes.idl:31
double pp
(4, 4) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:394
Time tm
Definition: ExtendedDataTypes.idl:624
Velocity3D data
Definition: ExtendedDataTypes.idl:605
double x
X value in metres.
Definition: ExtendedDataTypes.idl:219
double y
Yaw angle in radians.
Definition: ExtendedDataTypes.idl:237
Point in 3D cartesian space.
Definition: ExtendedDataTypes.idl:202
double ay
Acceleration along the y axis, in metres per second per second.
Definition: ExtendedDataTypes.idl:98
Covariance matrix for a 2D pose.
Definition: ExtendedDataTypes.idl:140
Time-stamped version of Pose2D.
Definition: ExtendedDataTypes.idl:462
Time tm
Definition: ExtendedDataTypes.idl:674
Velocity2D data
Definition: ExtendedDataTypes.idl:475
double xy
(0, 1) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:360
Time tm
Definition: ExtendedDataTypes.idl:684
Quaternion data
Definition: ExtendedDataTypes.idl:717
Time-stamped version of PoseVel2D.
Definition: ExtendedDataTypes.idl:492
RGBColour data
Definition: ExtendedDataTypes.idl:435
Pose3D pose
Definition: ExtendedDataTypes.idl:346
Time-stamped version of PointCovariance2D.
Definition: ExtendedDataTypes.idl:532
double y
Definition: ExtendedDataTypes.idl:705
double yy
(1, 1) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:149
Time-stamped version of SpeedHeading2D.
Definition: ExtendedDataTypes.idl:552
Time-stamped version of Size2D.
Definition: ExtendedDataTypes.idl:502
double za
(2, 5) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:386
Time-stamped version of Geometry2D.
Definition: ExtendedDataTypes.idl:512
double xr
(0, 3) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:364
Time tm
Definition: ExtendedDataTypes.idl:524
double y
Y value in metres.
Definition: ExtendedDataTypes.idl:221
Time tm
Definition: ExtendedDataTypes.idl:716
double aaz
Acceleration around the z axis, in radians per second per second.
Definition: ExtendedDataTypes.idl:311
double xt
(0, 2) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:147
double y
Y coordinate in metres.
Definition: ExtendedDataTypes.idl:48
Time-stamped version of Acceleration2D.
Definition: ExtendedDataTypes.idl:482
Point3D data
Definition: ExtendedDataTypes.idl:565
Geometry2D data
Definition: ExtendedDataTypes.idl:515
Velocities in 2D cartesian space.
Definition: ExtendedDataTypes.idl:79
Time tm
Definition: ExtendedDataTypes.idl:654
Pose2D data
Definition: ExtendedDataTypes.idl:465
double y
Y coordinate in metres.
Definition: ExtendedDataTypes.idl:207
Acceleration3D data
Definition: ExtendedDataTypes.idl:625
Velocity2D velocities
Definition: ExtendedDataTypes.idl:108
Pose2D pose
Definition: ExtendedDataTypes.idl:131
double avz
Velocity around the z axis, in radians per second.
Definition: ExtendedDataTypes.idl:283
Angular velocities in 3D cartesian space.
Definition: ExtendedDataTypes.idl:276
Definition: ExtendedDataTypes.idl:342
double speed
Speed in metres per second.
Definition: ExtendedDataTypes.idl:177
Velocity3D velocities
Definition: ExtendedDataTypes.idl:321
double yy
(1, 1) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:167
Time-stamped version of Point3D.
Definition: ExtendedDataTypes.idl:562
Geometry3D data
Definition: ExtendedDataTypes.idl:665
double p
Pitch angle in radians.
Definition: ExtendedDataTypes.idl:235
Time-stamped version of Velocity3D.
Definition: ExtendedDataTypes.idl:602
Time tm
Definition: ExtendedDataTypes.idl:514
double vx
Velocity along the x axis in metres per second.
Definition: ExtendedDataTypes.idl:82
Pose in 3D cartesian space.
Definition: ExtendedDataTypes.idl:244
Time tm
Definition: ExtendedDataTypes.idl:484
double speed
Speed in metres per second.
Definition: ExtendedDataTypes.idl:408
Carlike data
Definition: ExtendedDataTypes.idl:545
Vector3D position
Definition: ExtendedDataTypes.idl:421
Orientation3D direction
Direction of travel.
Definition: ExtendedDataTypes.idl:410
Control specification for a robot capable of moving in a given direction in 3D space.
Definition: ExtendedDataTypes.idl:405
double r
Roll angle in radians.
Definition: ExtendedDataTypes.idl:233
double va
Yaw velocity in radians per second.
Definition: ExtendedDataTypes.idl:269
Pose3D data
Definition: ExtendedDataTypes.idl:595
Red/green/blue colour specification, with values between 0.0 for none and 1.0 for full...
Definition: ExtendedDataTypes.idl:28
double vz
Velocity along the z axis in metres per second.
Definition: ExtendedDataTypes.idl:263
Time tm
Definition: ExtendedDataTypes.idl:664
double zz
(2, 2) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:380
double steeringAngle
Steering angle in radians.
Definition: ExtendedDataTypes.idl:179
double ay
Acceleration along the y axis, in metres per second per second.
Definition: ExtendedDataTypes.idl:295
double heading
Direction of travel in radians from the x axis.
Definition: ExtendedDataTypes.idl:191
Point3D position
3D position.
Definition: ExtendedDataTypes.idl:247
double heading
Heading in radians.
Definition: ExtendedDataTypes.idl:72
Vector3D approach
Definition: ExtendedDataTypes.idl:420
Angular accelerations in 3D cartesian space.
Definition: ExtendedDataTypes.idl:304
double aa
(5, 5) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:398
Vector in 2D cartesian space.
Definition: ExtendedDataTypes.idl:55
double ax
Acceleration along the x axis, in metres per second per second.
Definition: ExtendedDataTypes.idl:96
double l
Length in metres.
Definition: ExtendedDataTypes.idl:331
Time tm
Definition: ExtendedDataTypes.idl:454
Time tm
Definition: ExtendedDataTypes.idl:594
double z
Definition: ExtendedDataTypes.idl:706
Size3D size
Size of the device, taken with the origin at its base point.
Definition: ExtendedDataTypes.idl:348
PoseVel2D data
Definition: ExtendedDataTypes.idl:495
double va
Yaw velocity in radians per second.
Definition: ExtendedDataTypes.idl:86
double aax
Acceleration around the x axis, in radians per second per second.
Definition: ExtendedDataTypes.idl:307
double z
Z value in metres.
Definition: ExtendedDataTypes.idl:223
Time-stamped version of Vector3D.
Definition: ExtendedDataTypes.idl:572
Time-stamped version of OAP.
Definition: ExtendedDataTypes.idl:692
double xy
(0, 1) value of the covariance matrix.
Definition: ExtendedDataTypes.idl:165
Accelerations in 2D cartesian space.
Definition: ExtendedDataTypes.idl:93
Time-stamped version of Covariance3D.
Definition: ExtendedDataTypes.idl:672