forked from n-ando/OpenRTM-aist
/
ExtendedDataTypes.idl
749 lines (686 loc) · 16.5 KB
/
ExtendedDataTypes.idl
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
// -*- IDL -*-
/*!
* @file ExtendedDataTypes.idl
* @brief Extended data types for robotics applications.
* @date $Date: $
* @author Geoffrey Biggs <geoffrey.biggs@aist.go.jp>
*
* Copyright (C) 2009
* RT Synthesis Research Group
* Intelligent Systems Research Institute,
* National Institute of
* Advanced Industrial Science and Technology (AIST), Japan
* All rights reserved.
*
*/
#ifndef ExtendedDataTypes_idl
#define ExtendedDataTypes_idl
#include "BasicDataType.idl"
module RTC {
/*!
* @struct RGBColour
* @brief Red/green/blue colour specification, with values between 0.0 for
* none and 1.0 for full.
*/
struct RGBColour
{
double r;
double g;
double b;
};
//------------------------------------------------------------
// 2D data types
//------------------------------------------------------------
/*!
* @struct Point2D
* @brief Point in 2D cartesian space.
*/
struct Point2D
{
/// X coordinate in metres.
double x;
/// Y coordinate in metres.
double y;
};
/*!
* @struct Vector2D
* @brief Vector in 2D cartesian space.
*/
struct Vector2D
{
/// X value in metres.
double x;
/// Y value in metres.
double y;
};
/*!
* @struct Pose2D
* @brief Pose in 2D cartesian space.
*/
struct Pose2D
{
/// 2D position.
Point2D position;
/// Heading in radians.
double heading;
};
/*!
* @struct Velocity2D
* @brief Velocities in 2D cartesian space.
*/
struct Velocity2D
{
/// Velocity along the x axis in metres per second.
double vx;
/// Velocity along the y axis in metres per second.
double vy;
/// Yaw velocity in radians per second.
double va;
};
/*!
* @struct Acceleration2D
* @brief Accelerations in 2D cartesian space.
*/
struct Acceleration2D
{
/// Acceleration along the x axis, in metres per second per second.
double ax;
/// Acceleration along the y axis, in metres per second per second.
double ay;
};
/*!
* @struct PoseVel2D
* @brief Pose and velocity in 2D cartesian space.
*/
struct PoseVel2D
{
Pose2D pose;
Velocity2D velocities;
};
/*!
* @struct Size2D
* @brief Size in 2D cartesian space.
*/
struct Size2D
{
/// Length in metres.
double l;
/// Width in metres.
double w;
};
/*!
* @struct Geometry2D
* @brief Geometry information for a device in 2D cartesian space.
*/
struct Geometry2D
{
/// Pose of the device's base point in its parent device's (e.g. the robot's)
/// coordinate space.
Pose2D pose;
/// Size of the device, taken with the origin at its base point.
Size2D size;
};
/*!
* @struct Covariance2D
* @brief Covariance matrix for a 2D pose.
*/
struct Covariance2D
{
/// (0, 0) value of the covariance matrix.
double xx;
/// (0, 1) value of the covariance matrix.
double xy;
/// (0, 2) value of the covariance matrix.
double xt;
/// (1, 1) value of the covariance matrix.
double yy;
/// (1, 2) value of the covariance matrix.
double yt;
/// (2, 2) value of the covariance matrix.
double tt;
};
/*!
* @struct PointCovariance2D
* @brief Covariance matrix for a 2D point.
*/
struct PointCovariance2D
{
/// (0, 0) value of the covariance matrix.
double xx;
/// (0, 1) value of the covariance matrix.
double xy;
/// (1, 1) value of the covariance matrix.
double yy;
};
/*!
* @struct Carlike
* @brief Control specification for a car-like robot.
*/
struct Carlike
{
/// Speed in metres per second.
double speed;
/// Steering angle in radians.
double steeringAngle;
};
/*!
* @struct SpeedHeading2D
* @brief Control specification for a robot capable of moving in a given direction in 2D space.
*/
struct SpeedHeading2D
{
/// Speed in metres per second.
double speed;
/// Direction of travel in radians from the x axis.
double heading;
};
//------------------------------------------------------------
// 3D data types
//------------------------------------------------------------
/*!
* @struct Point3D
* @brief Point in 3D cartesian space.
*/
struct Point3D
{
/// X coordinate in metres.
double x;
/// Y coordinate in metres.
double y;
/// Z coordinate in metres.
double z;
};
/*!
* @struct Vector3D
* @brief Vector in 3D cartesian space.
*/
struct Vector3D
{
/// X value in metres.
double x;
/// Y value in metres.
double y;
/// Z value in metres.
double z;
};
/*!
* @struct Orientation3D
* @brief Orientation in 3D cartesian space.
*/
struct Orientation3D
{
/// Roll angle in radians.
double r;
/// Pitch angle in radians.
double p;
/// Yaw angle in radians.
double y;
};
/*!
* @struct Pose3D
* @brief Pose in 3D cartesian space.
*/
struct Pose3D
{
/// 3D position.
Point3D position;
/// 3D orientation.
Orientation3D orientation;
};
/*!
* @struct Velocity3D
* @brief Velocities in 3D cartesian space.
*/
struct Velocity3D
{
/// Velocity along the x axis in metres per second.
double vx;
/// Velocity along the y axis in metres per second.
double vy;
/// Velocity along the z axis in metres per second.
double vz;
/// Roll velocity in radians per second.
double vr;
/// Pitch velocity in radians per second.
double vp;
/// Yaw velocity in radians per second.
double va;
};
/*!
* @struct AngularVelocity3D
* @brief Angular velocities in 3D cartesian space.
*/
struct AngularVelocity3D
{
/// Velocity around the x axis, in radians per second.
double avx;
/// Velocity around the y axis, in radians per second.
double avy;
/// Velocity around the z axis, in radians per second.
double avz;
};
/*!
* @struct Acceleration3D
* @brief Accelerations in 3D cartesian space.
*/
struct Acceleration3D
{
/// Acceleration along the x axis, in metres per second per second.
double ax;
/// Acceleration along the y axis, in metres per second per second.
double ay;
/// Acceleration along the z axis, in metres per second per second.
double az;
};
/*!
* @struct AngularAcceleration3D
* @brief Angular accelerations in 3D cartesian space.
*/
struct AngularAcceleration3D
{
/// Acceleration around the x axis, in radians per second per second.
double aax;
/// Acceleration around the y axis, in radians per second per second.
double aay;
/// Acceleration around the z axis, in radians per second per second.
double aaz;
};
/*!
* @struct PoseVel3D
* @brief Pose and velocity in 3D cartesian space.
*/
struct PoseVel3D
{
Pose3D pose;
Velocity3D velocities;
};
/*!
* @struct Size3D
* @brief Size in 3D cartesian space.
*/
struct Size3D
{
/// Length in metres.
double l;
/// Width in metres.
double w;
/// Height in metres.
double h;
};
/*!
* @struct Geoemtry3D
* @brief Geometry information for a device in 3D cartesian space.
*/
struct Geometry3D
{
/// Pose of the device's base point in its parent device's (e.g. the robot's)
/// coordinate space.
Pose3D pose;
/// Size of the device, taken with the origin at its base point.
Size3D size;
};
/*!
* @struct Covariance3D
* @brief Covariance matrix for a 3D pose.
*/
struct Covariance3D
{
/// (0, 0) value of the covariance matrix.
double xx;
/// (0, 1) value of the covariance matrix.
double xy;
/// (0, 2) value of the covariance matrix.
double xz;
/// (0, 3) value of the covariance matrix.
double xr;
/// (0, 4) value of the covariance matrix.
double xp;
/// (0, 5) value of the covariance matrix.
double xa;
/// (1, 1) value of the covariance matrix.
double yy;
/// (1, 2) value of the covariance matrix.
double yz;
/// (1, 3) value of the covariance matrix.
double yr;
/// (1, 4) value of the covariance matrix.
double yp;
/// (1, 5) value of the covariance matrix.
double ya;
/// (2, 2) value of the covariance matrix.
double zz;
/// (2, 3) value of the covariance matrix.
double zr;
/// (2, 4) value of the covariance matrix.
double zp;
/// (2, 5) value of the covariance matrix.
double za;
/// (3, 3) value of the covariance matrix.
double rr;
/// (3, 4) value of the covariance matrix.
double rp;
/// (3, 5) value of the covariance matrix.
double ra;
/// (4, 4) value of the covariance matrix.
double pp;
/// (4, 5) value of the covariance matrix.
double pa;
/// (5, 5) value of the covariance matrix.
double aa;
};
/*!
* @struct SpeedHeading3D
* @brief Control specification for a robot capable of moving in a given direction in 3D space.
*/
struct SpeedHeading3D
{
/// Speed in metres per second.
double speed;
/// Direction of travel.
Orientation3D direction;
};
/*!
* @struct OAP
* @brief Orientation, approach and position vectors.
*/
struct OAP
{
Vector3D orientation;
Vector3D approach;
Vector3D position;
};
//------------------------------------------------------------
// Timed data types
//------------------------------------------------------------
/*!
* @struct TimedRGBColour
* @brief Time-stamped version of RGBColour.
*/
struct TimedRGBColour
{
Time tm;
RGBColour data;
};
/*!
* @struct TimedPoint2D
* @brief Time-stamped version of Point2D.
*/
struct TimedPoint2D
{
Time tm;
Point2D data;
};
/*!
* @struct TimedVector2D
* @brief Time-stamped version of Vector2D.
*/
struct TimedVector2D
{
Time tm;
Vector2D data;
};
/*!
* @struct TimedPose2D
* @brief Time-stamped version of Pose2D.
*/
struct TimedPose2D
{
Time tm;
Pose2D data;
};
/*!
* @struct TimedVelocity2D
* @brief Time-stamped version of Velocity2D.
*/
struct TimedVelocity2D
{
Time tm;
Velocity2D data;
};
/*!
* @struct TimedAcceleration2D
* @brief Time-stamped version of Acceleration2D.
*/
struct TimedAcceleration2D
{
Time tm;
Acceleration2D data;
};
/*!
* @struct TimedPoseVel2D
* @brief Time-stamped version of PoseVel2D.
*/
struct TimedPoseVel2D
{
Time tm;
PoseVel2D data;
};
/*!
* @struct TimedSize2D
* @brief Time-stamped version of Size2D.
*/
struct TimedSize2D
{
Time tm;
Size2D data;
};
/*!
* @struct TimedGeometry2D
* @brief Time-stamped version of Geometry2D.
*/
struct TimedGeometry2D
{
Time tm;
Geometry2D data;
};
/*!
* @struct TimedCovariance2D
* @brief Time-stamped version of Covariance2D.
*/
struct TimedCovariance2D
{
Time tm;
Covariance2D data;
};
/*!
* @struct TimedPointCovariance2D
* @brief Time-stamped version of PointCovariance2D.
*/
struct TimedPointCovariance2D
{
Time tm;
PointCovariance2D data;
};
/*!
* @struct TimedCarlike
* @brief Time-stamped version of Carlike.
*/
struct TimedCarlike
{
Time tm;
Carlike data;
};
/*!
* @struct TimedSpeedHeading2D
* @brief Time-stamped version of SpeedHeading2D.
*/
struct TimedSpeedHeading2D
{
Time tm;
SpeedHeading2D data;
};
/*!
* @struct TimedPoint3D
* @brief Time-stamped version of Point3D.
*/
struct TimedPoint3D
{
Time tm;
Point3D data;
};
/*!
* @struct TimedVector3D
* @brief Time-stamped version of Vector3D.
*/
struct TimedVector3D
{
Time tm;
Vector3D data;
};
/*!
* @struct TimedOrientation3D
* @brief Time-stamped version of Orientation3D.
*/
struct TimedOrientation3D
{
Time tm;
Orientation3D data;
};
/*!
* @struct TimedPose3D
* @brief Time-stamped version of Pose3D.
*/
struct TimedPose3D
{
Time tm;
Pose3D data;
};
/*!
* @struct TimedVelocity3D
* @brief Time-stamped version of Velocity3D.
*/
struct TimedVelocity3D
{
Time tm;
Velocity3D data;
};
/*!
* @struct TimedAngularVelocity3D
* @brief Time-stamped version of AngularVelocity3D.
*/
struct TimedAngularVelocity3D
{
Time tm;
AngularVelocity3D data;
};
/*!
* @struct TimedAcceleration3D
* @brief Time-stamped version of Acceleration3D.
*/
struct TimedAcceleration3D
{
Time tm;
Acceleration3D data;
};
/*!
* @struct TimedAngularAcceleration3D
* @brief Time-stamped version of AngularAcceleration3D.
*/
struct TimedAngularAcceleration3D
{
Time tm;
AngularAcceleration3D data;
};
/*!
* @struct TimedPoseVel3D
* @brief Time-stamped version of PoseVel3D.
*/
struct TimedPoseVel3D
{
Time tm;
PoseVel3D data;
};
/*!
* @struct TimedSize3D
* @brief Time-stamped version of Size3D.
*/
struct TimedSize3D
{
Time tm;
Size3D data;
};
/*!
* @struct TimedGeometry3D
* @brief Time-stamped version of Geometry3D.
*/
struct TimedGeometry3D
{
Time tm;
Geometry3D data;
};
/*!
* @struct TimedCovariance3D
* @brief Time-stamped version of Covariance3D.
*/
struct TimedCovariance3D
{
Time tm;
Covariance3D data;
};
/*!
* @struct TimedSpeedHeading3D
* @brief Time-stamped version of SpeedHeading3D.
*/
struct TimedSpeedHeading3D
{
Time tm;
SpeedHeading3D data;
};
/*!
* @struct TimedOAP
* @brief Time-stamped version of OAP.
*/
struct TimedOAP
{
Time tm;
OAP data;
};
/*!
* @struct Quaternion
* @brief Data type for Quaternion
*/
struct Quaternion
{
double x;
double y;
double z;
double w;
};
/*!
* @struct TimedQuaternion
* @brief Timed version data type for Quaternion
*/
struct TimedQuaternion
{
Time tm;
Quaternion data;
};
#pragma keylist TimedRGBColour
#pragma keylist TimedPoint2D
#pragma keylist TimedVector2D
#pragma keylist TimedPose2D
#pragma keylist TimedVelocity2D
#pragma keylist TimedAcceleration2D
#pragma keylist TimedPoseVel2D
#pragma keylist TimedSize2D
#pragma keylist TimedGeometry2D
#pragma keylist TimedCovariance2D
#pragma keylist TimedPointCovariance2D
#pragma keylist TimedCarlike
#pragma keylist TimedSpeedHeading2D
#pragma keylist TimedPoint3D
#pragma keylist TimedVector3D
#pragma keylist TimedOrientation3D
#pragma keylist TimedPose3D
#pragma keylist TimedVelocity3D
#pragma keylist TimedAngularVelocity3D
#pragma keylist TimedAcceleration3D
#pragma keylist TimedAngularAcceleration3D
#pragma keylist TimedPoseVel3D
#pragma keylist TimedSize3D
#pragma keylist TimedGeometry3D
#pragma keylist TimedCovariance3D
#pragma keylist TimedSpeedHeading3D
#pragma keylist TimedOAP
};
#endif // ExtendedDataTypes_idl