00001
00017 #ifndef InterfaceDataTypes_idl
00018 #define InterfaceDataTypes_idl
00019
00020 #include "BasicDataType.idl"
00021 #include "ExtendedDataTypes.idl"
00022
00023 module RTC {
00024
00025
00026
00027
00032 struct ActArrayActuatorPos
00033 {
00035 Time tm;
00037 unsigned short index;
00039 double position;
00040 };
00041
00046 struct ActArrayActuatorSpeed
00047 {
00049 Time tm;
00051 unsigned short index;
00053 double speed;
00054 };
00055
00060 struct ActArrayActuatorCurrent
00061 {
00063 Time tm;
00065 unsigned short index;
00067 double current;
00068 };
00069
00074 enum ActArrayActuatorStatus {ACTUATOR_STATUS_IDLE,
00075 ACTUATOR_STATUS_MOVING,
00076 ACTUATOR_STATUS_BRAKED,
00077 ACTUATOR_STATUS_STALLED};
00078
00083 struct Actuator
00084 {
00087 double position;
00089 double speed;
00091 double accel;
00093 double current;
00095 ActArrayActuatorStatus status;
00096 };
00097
00102 typedef sequence<Actuator> ActuatorList;
00107 struct ActArrayState
00108 {
00110 Time tm;
00112 ActuatorList actuators;
00113 };
00114
00119 enum ActArrayActuatorType {ACTARRAY_ACTUATORTYPE_LINEAR,
00120 ACTARRAY_ACTUATORTYPE_ROTARY};
00121
00126 struct ActArrayActuatorGeometry
00127 {
00129 ActArrayActuatorType type;
00132 double length;
00137 Orientation3D orientation;
00139 Vector3D axis;
00141 double minRange;
00143 double centre;
00145 double maxRange;
00147 double homePosition;
00149 boolean hasBrakes;
00150 };
00151
00156 typedef sequence<ActArrayActuatorGeometry> ActArrayActuatorGeometryList;
00157
00162 struct ActArrayGeometry
00163 {
00165 Geometry3D arrayGeometry;
00167 ActArrayActuatorGeometryList actuatorGeometry;
00168 };
00169
00170
00171
00172
00173
00178 struct BumperGeometry
00179 {
00181 Pose3D pose;
00183 Size3D size;
00185 double roc;
00186 };
00187
00191 typedef sequence<BumperGeometry> BumperGeometryList;
00192
00197 struct BumperArrayGeometry
00198 {
00200 Geometry3D arrayGeometry;
00202 BumperGeometryList bumperGeometry;
00203 };
00204
00205
00206
00207
00208
00213 struct CameraImage
00214 {
00216 Time tm;
00218 unsigned short width;
00220 unsigned short height;
00222 unsigned short bpp;
00224 string format;
00226 double fDiv;
00228 sequence<octet> pixels;
00229 };
00230
00235 struct CameraInfo
00236 {
00238 Vector2D focalLength;
00240 Point2D principalPoint;
00242 double k1;
00244 double k2;
00246 double p1;
00248 double p2;
00249 };
00250
00251
00252
00253
00254
00259 struct FiducialInfo
00260 {
00262 unsigned long id;
00264 Pose3D pose;
00266 Pose3D poseUncertainty;
00268 Size3D size;
00270 Size3D sizeUncertainty;
00271 };
00272
00276 typedef sequence<FiducialInfo> FiducialInfoList;
00277
00282 struct Fiducials
00283 {
00285 Time tm;
00287 FiducialInfoList fiducialsList;
00288 };
00289
00294 struct FiducialFOV
00295 {
00297 double minRange;
00299 double maxRange;
00301 double viewAngle;
00302 };
00303
00304
00305
00306
00307
00312 struct GPSTime
00313 {
00315 unsigned long sec;
00317 unsigned long msec;
00318 };
00319
00323 enum GPSFixType {GPS_FIX_NONE,
00324 GPS_FIX_NORMAL,
00325 GPS_FIX_DGPS};
00326
00331 struct GPSData
00332 {
00334 Time tm;
00336 GPSTime timeFromGPS;
00338 double latitude;
00340 double longitude;
00342 double altitude;
00344 double horizontalError;
00346 double verticalError;
00348 double heading;
00350 double horizontalSpeed;
00352 double verticalSpeed;
00354 unsigned short numSatellites;
00356 GPSFixType fixType;
00357 };
00358
00359
00360
00361
00362
00367 enum GripperStatus {GRIPPER_STATE_OPEN,
00368 GRIPPER_STATE_CLOSED,
00369 GRIPPER_STATE_MOVING,
00370 GRIPPER_STATE_UNKNOWN};
00371
00376 struct GripperState
00377 {
00379 Time tm;
00381 GripperStatus status;
00382 };
00383
00388 struct GripperGeometry
00389 {
00391 Geometry3D exterior;
00393 Geometry3D interior;
00394 };
00395
00396
00397
00398
00399
00404 struct INSData
00405 {
00407 Time tm;
00409 double latitude;
00411 double longitude;
00413 double altitude;
00415 double heightAMSL;
00417 Velocity3D velocityENU;
00419 Orientation3D orientation;
00420 };
00421
00422
00423
00424
00425
00429 enum LimbStatus {LIMB_STATUS_IDLE,
00430 LIMB_STATUS_BRAKED,
00431 LIMB_STATUS_MOVING,
00432 LIMB_STATUS_OOR,
00433 LIMB_STATUS_COLLISION};
00434
00439 struct LimbState
00440 {
00442 Time tm;
00444 OAP oapMatrix;
00446 LimbStatus status;
00447 };
00448
00449
00450
00451
00452
00457 struct Hypothesis2D
00458 {
00460 Pose2D mean;
00462 Covariance2D covariance;
00464 double weight;
00465 };
00466
00470 typedef sequence<Hypothesis2D> Hypothesis2DList;
00471
00476 struct Hypotheses2D
00477 {
00479 Time tm;
00481 Hypothesis2DList hypotheses;
00482 };
00483
00488 struct Hypothesis3D
00489 {
00491 Pose3D mean;
00493 Covariance3D covariance;
00495 double weight;
00496 };
00497
00501 typedef sequence<Hypothesis3D> Hypothesis3DList;
00502
00507 struct Hypotheses3D
00508 {
00510 Time tm;
00512 Hypothesis3DList hypotheses;
00513 };
00514
00515
00516
00517
00518
00523 struct OGMapConfig
00524 {
00526 double xScale;
00528 double yScale;
00530 unsigned long width;
00532 unsigned long height;
00534 Pose2D origin;
00535 };
00536
00540 typedef sequence<octet> OGMapCells;
00541
00546 struct OGMapTile
00547 {
00549 unsigned long column;
00551 unsigned long row;
00553 unsigned long width;
00555 unsigned long height;
00557 OGMapCells cells;
00558 };
00559
00564 struct PointFeature
00565 {
00567 double probability;
00569 Point2D position;
00571 PointCovariance2D covariance;
00572 };
00576 typedef sequence<PointFeature> PointFeatureList;
00577
00582 struct PoseFeature
00583 {
00585 double probability;
00587 Pose2D position;
00589 Covariance2D covariance;
00590 };
00594 typedef sequence<PoseFeature> PoseFeatureList;
00595
00600 struct LineFeature
00601 {
00603 double probability;
00605 double rho;
00607 double alpha;
00609 PointCovariance2D covariance;
00611 Point2D start;
00613 Point2D end;
00615 boolean startSighted;
00617 boolean endSighted;
00618 };
00622 typedef sequence<LineFeature> LineFeatureList;
00623
00628 struct Features
00629 {
00631 Time tm;
00633 PointFeatureList pointFeatures;
00635 PoseFeatureList poseFeatures;
00637 LineFeatureList lineFeatures;
00638 };
00639
00640
00641
00642
00643
00647 typedef sequence<CameraImage> MulticameraImageList;
00652 struct MultiCameraImages
00653 {
00655 Time tm;
00657 MulticameraImageList images;
00658 };
00659
00663 typedef sequence<CameraInfo> MulticameraInfoList;
00664
00668 typedef sequence<Geometry3D> MulticameraGeometryList;
00669
00674 struct MulticameraGeometry
00675 {
00677 Geometry3D geometry;
00679 MulticameraGeometryList cameraGeometries;
00680 };
00681
00682
00683
00684
00685
00690 struct Waypoint2D
00691 {
00693 Pose2D target;
00695 double distanceTolerance;
00697 double headingTolerance;
00699 Time timeLimit;
00701 Velocity2D maxSpeed;
00702 };
00703
00707 typedef sequence<Waypoint2D> Waypoint2DList;
00708
00713 struct Path2D
00714 {
00716 Time tm;
00718 Waypoint2DList waypoints;
00719 };
00720
00725 struct Waypoint3D
00726 {
00728 Pose3D target;
00730 double distanceTolerance;
00732 double headingTolerance;
00734 Time timeLimit;
00736 Velocity3D maxSpeed;
00737 };
00738
00742 typedef sequence<Waypoint3D> Waypoint3DList;
00743
00748 struct Path3D
00749 {
00751 Time tm;
00753 Waypoint3DList waypoints;
00754 };
00755
00756
00757
00758
00759
00764 struct PointCloudPoint
00765 {
00767 Point3D point;
00769 RGBColour colour;
00770 };
00771
00775 typedef sequence<PointCloudPoint> PointCloudPointList;
00776
00781 struct PointCloud
00782 {
00784 Time tm;
00786 PointCloudPointList points;
00787 };
00788
00789
00790
00791
00792
00797 struct PanTiltAngles
00798 {
00800 Time tm;
00802 double pan;
00804 double tilt;
00805 };
00806
00811 struct PanTiltState
00812 {
00814 Time tm;
00816 PanTiltAngles angles;
00818 double panSpeed;
00820 double tiltSpeed;
00821 };
00822
00823
00824
00825
00826
00830 typedef sequence<Geometry3D> ElementGeometryList;
00831
00840 struct RangerGeometry
00841 {
00843 Geometry3D geometry;
00846 ElementGeometryList elementGeometries;
00847 };
00848
00853 struct RangerConfig
00854 {
00856 double minAngle;
00858 double maxAngle;
00860 double angularRes;
00862 double minRange;
00864 double maxRange;
00866 double rangeRes;
00868 double frequency;
00869 };
00870
00874 typedef sequence<double> RangeList;
00875
00880 struct RangeData
00881 {
00883 Time tm;
00885 RangeList ranges;
00887 RangerGeometry geometry;
00889 RangerConfig config;
00890 };
00891
00895 typedef sequence<double> IntensityList;
00896
00901 struct IntensityData
00902 {
00904 Time tm;
00906 IntensityList intensities;
00908 RangerGeometry geometry;
00910 RangerConfig config;
00911 };
00912
00913
00914
00915
00916
00920 typedef sequence<octet> RFIDTagData;
00921 };
00922
00923 #endif // InterfaceDataTypes_idl