OpenRTM-aist IDL  1.2
InterfaceDataTypes.idl
Go to the documentation of this file.
1 // -*- IDL -*-
17 #ifndef InterfaceDataTypes_idl
18 #define InterfaceDataTypes_idl
19 
20 #include "BasicDataType.idl"
21 #include "ExtendedDataTypes.idl"
22 
23 module RTC {
24  //------------------------------------------------------------
25  // ActArray
26  //------------------------------------------------------------
27 
33  {
37  unsigned short index;
39  double position;
40  };
41 
47  {
51  unsigned short index;
53  double speed;
54  };
55 
61  {
65  unsigned short index;
67  double current;
68  };
69 
78 
83  struct Actuator
84  {
87  double position;
89  double speed;
91  double accel;
93  double current;
96  };
97 
102  typedef sequence<Actuator> ActuatorList;
108  {
112  ActuatorList actuators;
113  };
114 
121 
127  {
132  double length;
141  double minRange;
143  double centre;
145  double maxRange;
147  double homePosition;
149  boolean hasBrakes;
150  };
151 
156  typedef sequence<ActArrayActuatorGeometry> ActArrayActuatorGeometryList;
157 
163  {
167  ActArrayActuatorGeometryList actuatorGeometry;
168  };
169 
170  //------------------------------------------------------------
171  // Bumper
172  //------------------------------------------------------------
173 
179  {
185  double roc;
186  };
187 
191  typedef sequence<BumperGeometry> BumperGeometryList;
192 
198  {
202  BumperGeometryList bumperGeometry;
203  };
204 
205  //------------------------------------------------------------
206  // Camera
207  //------------------------------------------------------------
208 
213  struct CameraImage
214  {
218  unsigned short width;
220  unsigned short height;
222  unsigned short bpp;
224  string format;
226  double fDiv;
228  sequence<octet> pixels;
229  };
230 
235  struct CameraInfo
236  {
242  double k1;
244  double k2;
246  double p1;
248  double p2;
249  };
250 
251  //------------------------------------------------------------
252  // Fiducial
253  //------------------------------------------------------------
254 
260  {
262  unsigned long id;
271  };
272 
276  typedef sequence<FiducialInfo> FiducialInfoList;
277 
282  struct Fiducials
283  {
287  FiducialInfoList fiducialsList;
288  };
289 
294  struct FiducialFOV
295  {
297  double minRange;
299  double maxRange;
301  double viewAngle;
302  };
303 
304  //------------------------------------------------------------
305  // GPS
306  //------------------------------------------------------------
307 
312  struct GPSTime
313  {
315  unsigned long sec;
317  unsigned long msec;
318  };
319 
326 
331  struct GPSData
332  {
338  double latitude;
340  double longitude;
342  double altitude;
348  double heading;
354  unsigned short numSatellites;
357  };
358 
359  //------------------------------------------------------------
360  // Gripper
361  //------------------------------------------------------------
362 
371 
377  {
382  };
383 
389  {
394  };
395 
396  //------------------------------------------------------------
397  // INS
398  //------------------------------------------------------------
399 
404  struct INSData
405  {
409  double latitude;
411  double longitude;
413  double altitude;
415  double heightAMSL;
420  };
421 
422  //------------------------------------------------------------
423  // Limb
424  //------------------------------------------------------------
425 
434 
439  struct LimbState
440  {
447  };
448 
449  //------------------------------------------------------------
450  // Localise
451  //------------------------------------------------------------
452 
458  {
464  double weight;
465  };
466 
470  typedef sequence<Hypothesis2D> Hypothesis2DList;
471 
477  {
481  Hypothesis2DList hypotheses;
482  };
483 
489  {
495  double weight;
496  };
497 
501  typedef sequence<Hypothesis3D> Hypothesis3DList;
502 
508  {
512  Hypothesis3DList hypotheses;
513  };
514 
515  //------------------------------------------------------------
516  // Map
517  //------------------------------------------------------------
518 
523  struct OGMapConfig
524  {
526  double xScale;
528  double yScale;
530  unsigned long width;
532  unsigned long height;
535  };
536 
540  typedef sequence<octet> OGMapCells;
541 
546  struct OGMapTile
547  {
549  unsigned long column;
551  unsigned long row;
553  unsigned long width;
555  unsigned long height;
557  OGMapCells cells;
558  };
559 
565  {
567  double probability;
572  };
576  typedef sequence<PointFeature> PointFeatureList;
577 
582  struct PoseFeature
583  {
585  double probability;
590  };
594  typedef sequence<PoseFeature> PoseFeatureList;
595 
600  struct LineFeature
601  {
603  double probability;
605  double rho;
607  double alpha;
615  boolean startSighted;
617  boolean endSighted;
618  };
622  typedef sequence<LineFeature> LineFeatureList;
623 
628  struct Features
629  {
633  PointFeatureList pointFeatures;
635  PoseFeatureList poseFeatures;
637  LineFeatureList lineFeatures;
638  };
639 
640  //------------------------------------------------------------
641  // Multicamera
642  //------------------------------------------------------------
643 
647  typedef sequence<CameraImage> MulticameraImageList;
653  {
657  MulticameraImageList images;
658  };
659 
663  typedef sequence<CameraInfo> MulticameraInfoList;
664 
668  typedef sequence<Geometry3D> MulticameraGeometryList;
669 
675  {
679  MulticameraGeometryList cameraGeometries;
680  };
681 
682  //------------------------------------------------------------
683  // Paths
684  //------------------------------------------------------------
685 
690  struct Waypoint2D
691  {
702  };
703 
707  typedef sequence<Waypoint2D> Waypoint2DList;
708 
713  struct Path2D
714  {
718  Waypoint2DList waypoints;
719  };
720 
725  struct Waypoint3D
726  {
737  };
738 
742  typedef sequence<Waypoint3D> Waypoint3DList;
743 
748  struct Path3D
749  {
753  Waypoint3DList waypoints;
754  };
755 
756  //------------------------------------------------------------
757  // PointCloud
758  //------------------------------------------------------------
759 
765  {
770  };
771 
775  typedef sequence<PointCloudPoint> PointCloudPointList;
776 
781  struct PointCloud
782  {
786  PointCloudPointList points;
787  };
788 
789  //------------------------------------------------------------
790  // PanTilt
791  //------------------------------------------------------------
792 
798  {
802  double pan;
804  double tilt;
805  };
806 
812  {
818  double panSpeed;
820  double tiltSpeed;
821  };
822 
823  //------------------------------------------------------------
824  // Ranger
825  //------------------------------------------------------------
826 
830  typedef sequence<Geometry3D> ElementGeometryList;
831 
841  {
846  ElementGeometryList elementGeometries;
847  };
848 
854  {
856  double minAngle;
858  double maxAngle;
860  double angularRes;
862  double minRange;
864  double maxRange;
866  double rangeRes;
868  double frequency;
869  };
870 
874  typedef sequence<double> RangeList;
875 
880  struct RangeData
881  {
885  RangeList ranges;
890  };
891 
895  typedef sequence<double> IntensityList;
896 
902  {
906  IntensityList intensities;
911  };
912 
913  //------------------------------------------------------------
914  // RFID
915  //------------------------------------------------------------
916 
920  typedef sequence<octet> RFIDTagData;
921 };
922 
923 #endif // InterfaceDataTypes_idl
Point2D end
End point of the line segment.
Definition: InterfaceDataTypes.idl:613
Point2D principalPoint
Principal point of the camera.
Definition: InterfaceDataTypes.idl:240
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:784
A tile from an occupancy-grid map.
Definition: InterfaceDataTypes.idl:546
double speed
Current speed of the actuator, in metres per second or radians per second.
Definition: InterfaceDataTypes.idl:89
A cloud of points in 3D space.
Definition: InterfaceDataTypes.idl:781
Waypoint2DList waypoints
The sequence of waypoints that make up the path.
Definition: InterfaceDataTypes.idl:718
Hypothesis2DList hypotheses
List of hypotheses.
Definition: InterfaceDataTypes.idl:481
Definition: InterfaceDataTypes.idl:430
Point2D start
Start point of the line segment.
Definition: InterfaceDataTypes.idl:611
double p2
Tangential distortion coefficient 2.
Definition: InterfaceDataTypes.idl:248
sequence< double > RangeList
Definition: InterfaceDataTypes.idl:874
double headingTolerance
How much off the target heading is considered success (in radians).
Definition: InterfaceDataTypes.idl:697
double roc
Radius of curvature of the bump sensor in metres. Zero if the bumper is a straight line...
Definition: InterfaceDataTypes.idl:185
Pose2D mean
Mean of the localisation hypothesis.
Definition: InterfaceDataTypes.idl:460
Vector2D focalLength
Focal length (x, y) in metres.
Definition: InterfaceDataTypes.idl:238
double distanceTolerance
How far away from the waypoint is considered success (radius in metres).
Definition: InterfaceDataTypes.idl:695
unsigned short index
Zero-based index of the actuator.
Definition: InterfaceDataTypes.idl:51
PointCovariance2D covariance
Covariance matrix of rho and alpha.
Definition: InterfaceDataTypes.idl:609
sequence< CameraImage > MulticameraImageList
Definition: InterfaceDataTypes.idl:647
RangerGeometry geometry
Geometry of the ranger at the time the scan data was measured.
Definition: InterfaceDataTypes.idl:908
double current
Current of the actuator in amps.
Definition: InterfaceDataTypes.idl:67
LimbStatus
Definition: InterfaceDataTypes.idl:429
double position
Definition: InterfaceDataTypes.idl:87
double longitude
Longitude in degrees.
Definition: InterfaceDataTypes.idl:340
Pose3D pose
Detected pose.
Definition: InterfaceDataTypes.idl:264
Definition: InterfaceDataTypes.idl:324
Definition: BasicDataType.idl:22
Waypoint3DList waypoints
The sequence of waypoints that make up the path.
Definition: InterfaceDataTypes.idl:753
Stores the position of a single actuator.
Definition: InterfaceDataTypes.idl:32
Size in 3D cartesian space.
Definition: ExtendedDataTypes.idl:328
sequence< Hypothesis2D > Hypothesis2DList
Definition: InterfaceDataTypes.idl:470
ActArrayActuatorType type
Type of the actuator.
Definition: InterfaceDataTypes.idl:129
Definition: InterfaceDataTypes.idl:120
Orientation, approach and position vectors.
Definition: ExtendedDataTypes.idl:417
sequence< PointFeature > PointFeatureList
Definition: InterfaceDataTypes.idl:576
Geometry3D arrayGeometry
Geometry of the entire array.
Definition: InterfaceDataTypes.idl:200
Geometry of a gripper, including both the outside and inside sizes.
Definition: InterfaceDataTypes.idl:388
Range readings from a range sensor.
Definition: InterfaceDataTypes.idl:880
A waypoint in 3D space, including constraints.
Definition: InterfaceDataTypes.idl:725
Point in 2D cartesian space.
Definition: ExtendedDataTypes.idl:43
double altitude
Altitude above the ellisoid in metres.
Definition: InterfaceDataTypes.idl:342
A size-less point feature.
Definition: InterfaceDataTypes.idl:564
unsigned short height
Image pixel height.
Definition: InterfaceDataTypes.idl:220
Covariance matrix for a 3D pose.
Definition: ExtendedDataTypes.idl:355
sequence< octet > OGMapCells
Definition: InterfaceDataTypes.idl:540
A time-stamped path in 2D space.
Definition: InterfaceDataTypes.idl:713
double maxRange
Maximum scannable range in metres.
Definition: InterfaceDataTypes.idl:864
Vector3D axis
The axis of rotation for this actuator if it is rotary, or axis along which it moves if it is linear...
Definition: InterfaceDataTypes.idl:139
Information about a single fiducial.
Definition: InterfaceDataTypes.idl:259
Geometry3D geometry
Overall geometry of the camera system.
Definition: InterfaceDataTypes.idl:677
Time-stamped state of a limb.
Definition: InterfaceDataTypes.idl:439
GripperStatus
Describes the status of a gripper.
Definition: InterfaceDataTypes.idl:367
unsigned long height
Number of cells along the y axis in this tile;.
Definition: InterfaceDataTypes.idl:555
LimbStatus status
Current status of the limb.
Definition: InterfaceDataTypes.idl:446
Velocity2D maxSpeed
Maximum sped to travel at while heading to the waypoint.
Definition: InterfaceDataTypes.idl:701
Orientation in 3D cartesian space.
Definition: ExtendedDataTypes.idl:230
PointCloudPointList points
The points in the cloud.
Definition: InterfaceDataTypes.idl:786
double homePosition
Home position of the actuator, in metres or radians.
Definition: InterfaceDataTypes.idl:147
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:49
Definition: InterfaceDataTypes.idl:433
double altitude
Altitude in metres.
Definition: InterfaceDataTypes.idl:413
Covariance2D covariance
Covariance matrix of the mean pose.
Definition: InterfaceDataTypes.idl:462
PointFeatureList pointFeatures
Point features.
Definition: InterfaceDataTypes.idl:633
RangerConfig config
Configuration of the ranger at the time the scan data was measured.
Definition: InterfaceDataTypes.idl:889
Geometry3D exterior
Geometry of the exterior of the gripper when open, in parent coordinate space.
Definition: InterfaceDataTypes.idl:391
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:285
Pan and tilt values of a pan-tilt unit.
Definition: InterfaceDataTypes.idl:797
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:631
RangeList ranges
Range values in metres.
Definition: InterfaceDataTypes.idl:885
Time timeLimit
Target time to arrive at the waypoint by.
Definition: InterfaceDataTypes.idl:699
Pose2D target
Location of the waypoint.
Definition: InterfaceDataTypes.idl:693
double horizontalError
One standard deviation in the horizontal position error, in metres.
Definition: InterfaceDataTypes.idl:344
sequence< Actuator > ActuatorList
List of Actuator elements.
Definition: InterfaceDataTypes.idl:102
double minRange
Minimum scannable range in metres.
Definition: InterfaceDataTypes.idl:862
A pose hypothesis in 3D space.
Definition: InterfaceDataTypes.idl:488
double alpha
Angle of the line vector from the x axis in radians.
Definition: InterfaceDataTypes.idl:607
double accel
Current acceleration of the actuator, in metres per second or radians per second. ...
Definition: InterfaceDataTypes.idl:91
GPSFixType
Definition: InterfaceDataTypes.idl:323
LineFeatureList lineFeatures
Line features.
Definition: InterfaceDataTypes.idl:637
Hypothesis3DList hypotheses
List of hypotheses.
Definition: InterfaceDataTypes.idl:512
Information about an image-producing device.
Definition: InterfaceDataTypes.idl:235
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:904
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:407
Velocity3D maxSpeed
Maximum sped to travel at while heading to the waypoint.
Definition: InterfaceDataTypes.idl:736
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:35
RangerConfig config
Configuration of the ranger at the time the scan data was measured.
Definition: InterfaceDataTypes.idl:910
Velocities in 3D cartesian space.
Definition: ExtendedDataTypes.idl:256
Pose in 2D cartesian space.
Definition: ExtendedDataTypes.idl:67
double headingTolerance
How much off the target heading is considered success (in radians).
Definition: InterfaceDataTypes.idl:732
Size3D size
Detected size.
Definition: InterfaceDataTypes.idl:268
MulticameraGeometryList cameraGeometries
Geometry of each camera.
Definition: InterfaceDataTypes.idl:679
Pose3D mean
Mean of the localisation hypothesis.
Definition: InterfaceDataTypes.idl:491
unsigned short width
Image pixel width.
Definition: InterfaceDataTypes.idl:218
Pose3D poseUncertainty
Uncertainty in the pose.
Definition: InterfaceDataTypes.idl:266
Definition: InterfaceDataTypes.idl:119
sequence< PoseFeature > PoseFeatureList
Definition: InterfaceDataTypes.idl:594
double minRange
Minimum range of motion of the actuator, in metres or radians.
Definition: InterfaceDataTypes.idl:141
IntensityList intensities
Intensity values normalised to between 0 and 1.
Definition: InterfaceDataTypes.idl:906
Covariance2D covariance
Covariance matrix of the pose.
Definition: InterfaceDataTypes.idl:589
Pose3D target
Location of the waypoint.
Definition: InterfaceDataTypes.idl:728
Definition: InterfaceDataTypes.idl:76
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:510
double angularRes
Angular resolution in radians.
Definition: InterfaceDataTypes.idl:860
double frequency
Scanning frequency in Hertz.
Definition: InterfaceDataTypes.idl:868
Definition: InterfaceDataTypes.idl:74
sequence< octet > pixels
Raw pixel data.
Definition: InterfaceDataTypes.idl:228
Describes the geometry of an individual actuator.
Definition: InterfaceDataTypes.idl:126
sequence< Waypoint2D > Waypoint2DList
Definition: InterfaceDataTypes.idl:707
Definition: InterfaceDataTypes.idl:370
double maxRange
Maximum range in metres at which fiducials can be detected.
Definition: InterfaceDataTypes.idl:299
Geometry3D interior
Geometry of the interior of the gripper when open, in gripper coordinate space.
Definition: InterfaceDataTypes.idl:393
RGBColour colour
The colour of the point, if any.
Definition: InterfaceDataTypes.idl:769
Geometry of an array of bump sensors.
Definition: InterfaceDataTypes.idl:197
sequence< Geometry3D > ElementGeometryList
Definition: InterfaceDataTypes.idl:830
sequence< octet > RFIDTagData
Definition: InterfaceDataTypes.idl:920
A point in a point cloud.
Definition: InterfaceDataTypes.idl:764
Intensity readings from a range sensor.
Definition: InterfaceDataTypes.idl:901
PointCovariance2D covariance
Covariance matrix of the position.
Definition: InterfaceDataTypes.idl:571
Pose2D origin
Pose of the cell at (0, 0) in the real world.
Definition: InterfaceDataTypes.idl:534
OAP oapMatrix
Orientation, approach and position of the end-effector.
Definition: InterfaceDataTypes.idl:444
unsigned long height
Number of cells along the y axis.
Definition: InterfaceDataTypes.idl:532
Vector in 3D cartesian space.
Definition: ExtendedDataTypes.idl:216
double rangeRes
Range resolution in metres.
Definition: InterfaceDataTypes.idl:866
GPSFixType fixType
The type of position fix this is.
Definition: InterfaceDataTypes.idl:356
Definition: InterfaceDataTypes.idl:628
Covariance matrix for a 2D point.
Definition: ExtendedDataTypes.idl:160
Definition: InterfaceDataTypes.idl:75
Extended data types for robotics applications.
ActuatorList actuators
Sequence of actuator states, one for each actuator.
Definition: InterfaceDataTypes.idl:112
FiducialInfoList fiducialsList
List of detected fiducials.
Definition: InterfaceDataTypes.idl:287
GripperStatus status
Status of the gripper.
Definition: InterfaceDataTypes.idl:381
double position
Position of the actuator in metres or radians.
Definition: InterfaceDataTypes.idl:39
Covariance3D covariance
Covariance matrix of the mean pose.
Definition: InterfaceDataTypes.idl:493
double maxAngle
Maximum scannable angle in radians.
Definition: InterfaceDataTypes.idl:858
Time-stamped list of detected fiducials.
Definition: InterfaceDataTypes.idl:282
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:800
Configuration of a occupancy-grip map.
Definition: InterfaceDataTypes.idl:523
MulticameraImageList images
Image list.
Definition: InterfaceDataTypes.idl:657
Definition: InterfaceDataTypes.idl:77
double length
Definition: InterfaceDataTypes.idl:132
PanTiltAngles angles
Pan and tilt angles.
Definition: InterfaceDataTypes.idl:816
State of all actuators in an array.
Definition: InterfaceDataTypes.idl:107
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:63
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:379
Pose3D pose
Pose of the bumper&#39;s base point in the array&#39;s coordinate space.
Definition: InterfaceDataTypes.idl:181
sequence< LineFeature > LineFeatureList
Definition: InterfaceDataTypes.idl:622
PoseFeatureList poseFeatures
Pose features.
Definition: InterfaceDataTypes.idl:635
Definition: BasicDataType.idl:26
double horizontalSpeed
Estimated horizontal speed in metres per second.
Definition: InterfaceDataTypes.idl:350
unsigned long width
Number of cells along the x axis.
Definition: InterfaceDataTypes.idl:530
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:479
boolean hasBrakes
True if the actuator has brakes.
Definition: InterfaceDataTypes.idl:149
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:216
unsigned long column
X coordinate of the (0, 0) cell of this tile in the whole map.
Definition: InterfaceDataTypes.idl:549
double pan
Pan value in radians.
Definition: InterfaceDataTypes.idl:802
Status of a pan-tilt unit.
Definition: InterfaceDataTypes.idl:811
Geometry3D arrayGeometry
Geometry of the overall array.
Definition: InterfaceDataTypes.idl:165
Geometry of a single bumper.
Definition: InterfaceDataTypes.idl:178
sequence< BumperGeometry > BumperGeometryList
Definition: InterfaceDataTypes.idl:191
sequence< PointCloudPoint > PointCloudPointList
Definition: InterfaceDataTypes.idl:775
A size-less point feature with orientation.
Definition: InterfaceDataTypes.idl:582
Definition: InterfaceDataTypes.idl:369
Time-stamped list of localisation hypotheses in 3D space.
Definition: InterfaceDataTypes.idl:507
Definition: InterfaceDataTypes.idl:323
double verticalError
One standard deviation in the vertical position error, in metres.
Definition: InterfaceDataTypes.idl:346
sequence< FiducialInfo > FiducialInfoList
Definition: InterfaceDataTypes.idl:276
ActArrayActuatorGeometryList actuatorGeometry
Geometry of the individual actuators.
Definition: InterfaceDataTypes.idl:167
double viewAngle
Receptive angle in radians of the sensor (centred about the forward direction).
Definition: InterfaceDataTypes.idl:301
double heading
Estimated heading from true north in radians.
Definition: InterfaceDataTypes.idl:348
State information of a single actuator.
Definition: InterfaceDataTypes.idl:83
Orientation3D orientation
Orientation, where east is 0.
Definition: InterfaceDataTypes.idl:419
unsigned short numSatellites
Number of satellites in view.
Definition: InterfaceDataTypes.idl:354
double tiltSpeed
Speed at which the pan-tilt unit is changing its tilt angle in radians per second.
Definition: InterfaceDataTypes.idl:820
double speed
Speed of the actuator in metres per second or radians per second.
Definition: InterfaceDataTypes.idl:53
unsigned short bpp
Bits per pixel.
Definition: InterfaceDataTypes.idl:222
sequence< ActArrayActuatorGeometry > ActArrayActuatorGeometryList
List of ActArrayActuatorGeometry elements.
Definition: InterfaceDataTypes.idl:156
Point in 3D cartesian space.
Definition: ExtendedDataTypes.idl:202
double latitude
Latitude in degrees.
Definition: InterfaceDataTypes.idl:338
double centre
Centre point of the actuator&#39;s range of motion, in metres or radians.
Definition: InterfaceDataTypes.idl:143
Covariance matrix for a 2D pose.
Definition: ExtendedDataTypes.idl:140
BumperGeometryList bumperGeometry
Geometry of each individual bumper.
Definition: InterfaceDataTypes.idl:202
unsigned long width
Number of cells along the x axis in this tile;.
Definition: InterfaceDataTypes.idl:553
Definition: InterfaceDataTypes.idl:325
double yScale
Scale on the y axis (metres per cell).
Definition: InterfaceDataTypes.idl:528
boolean endSighted
True if the end point of the line has been sighted (i.e. it is inside seen space).
Definition: InterfaceDataTypes.idl:617
Definition: InterfaceDataTypes.idl:429
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:716
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:655
Field of view of a fiducial tracker.
Definition: InterfaceDataTypes.idl:294
double weight
Weight of this hypothesis for mixing.
Definition: InterfaceDataTypes.idl:495
double distanceTolerance
How far away from the waypoint is considered success (radius in metres).
Definition: InterfaceDataTypes.idl:730
double xScale
Scale on the x axis (metres per cell).
Definition: InterfaceDataTypes.idl:526
Geometry of a multi-camera system, such as a stereo camera.
Definition: InterfaceDataTypes.idl:674
double current
Current draw of the actuator, in amps.
Definition: InterfaceDataTypes.idl:93
Size3D size
Size of the bumper.
Definition: InterfaceDataTypes.idl:183
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:334
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:442
A waypoint in 2D space, including constraints.
Definition: InterfaceDataTypes.idl:690
A pose hypothesis in 2D space.
Definition: InterfaceDataTypes.idl:457
ActArrayActuatorStatus status
Status of the actuator.
Definition: InterfaceDataTypes.idl:95
A time-stamped path in 3D space.
Definition: InterfaceDataTypes.idl:748
Geometry of a ranger device. A range sensor may be a single device returning multiple ranges (such as...
Definition: InterfaceDataTypes.idl:840
ActArrayActuatorType
Describes the type of an actuator.
Definition: InterfaceDataTypes.idl:119
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:751
double latitude
Latitude in degrees.
Definition: InterfaceDataTypes.idl:409
The configuration of a ranger device.
Definition: InterfaceDataTypes.idl:853
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:110
Definition: InterfaceDataTypes.idl:367
sequence< CameraInfo > MulticameraInfoList
Definition: InterfaceDataTypes.idl:663
Geometry of an actuator array.
Definition: InterfaceDataTypes.idl:162
double k2
Radial distortion coefficient 2.
Definition: InterfaceDataTypes.idl:244
Velocities in 2D cartesian space.
Definition: ExtendedDataTypes.idl:79
RangerGeometry geometry
Geometry of the ranger at the time the scan data was measured.
Definition: InterfaceDataTypes.idl:887
unsigned long msec
Microseconds value.
Definition: InterfaceDataTypes.idl:317
Stores the speed of a single actuator.
Definition: InterfaceDataTypes.idl:46
double minAngle
Minimum scannable angle in radians.
Definition: InterfaceDataTypes.idl:856
double k1
Radial distortion coefficient 1.
Definition: InterfaceDataTypes.idl:242
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:883
double rho
Length of the line vector in metres.
Definition: InterfaceDataTypes.idl:605
Size3D sizeUncertainty
Uncertainty in the size.
Definition: InterfaceDataTypes.idl:270
Definition: ExtendedDataTypes.idl:342
double tilt
Tilt value in radians.
Definition: InterfaceDataTypes.idl:804
double weight
Weight of this hypothesis for mixing.
Definition: InterfaceDataTypes.idl:464
Definition: InterfaceDataTypes.idl:431
double fDiv
Scale factor for images, such as disparity maps, where the integer pixel value should be divided by t...
Definition: InterfaceDataTypes.idl:226
double probability
Probability of the feature.
Definition: InterfaceDataTypes.idl:585
unsigned short index
Zero-based index of the actuator.
Definition: InterfaceDataTypes.idl:37
Data as returned by a common GPS device.
Definition: InterfaceDataTypes.idl:331
double p1
Tangential distortion coefficient 1.
Definition: InterfaceDataTypes.idl:246
Pose in 3D cartesian space.
Definition: ExtendedDataTypes.idl:244
sequence< Hypothesis3D > Hypothesis3DList
Definition: InterfaceDataTypes.idl:501
boolean startSighted
True if the start point of the line has been sighted (i.e. it is inside seen space).
Definition: InterfaceDataTypes.idl:615
Definition: InterfaceDataTypes.idl:652
double probability
Probability of the feature.
Definition: InterfaceDataTypes.idl:567
Definition: InterfaceDataTypes.idl:432
Pose2D position
Pose of the feature.
Definition: InterfaceDataTypes.idl:587
unsigned long sec
Seconds value.
Definition: InterfaceDataTypes.idl:315
double heightAMSL
Height above mean sea level in metres.
Definition: InterfaceDataTypes.idl:415
Stores an image from a camera or camera-like device.
Definition: InterfaceDataTypes.idl:213
double maxRange
Maximum range of motion of the actuator, in metres or radians.
Definition: InterfaceDataTypes.idl:145
Velocity3D velocityENU
Velocity east/north/up.
Definition: InterfaceDataTypes.idl:417
ElementGeometryList elementGeometries
Definition: InterfaceDataTypes.idl:846
string format
Image format (e.g. bitmap, jpeg, etc.).
Definition: InterfaceDataTypes.idl:224
unsigned short index
Zero-based index of the actuator.
Definition: InterfaceDataTypes.idl:65
Red/green/blue colour specification, with values between 0.0 for none and 1.0 for full...
Definition: ExtendedDataTypes.idl:28
Geometry3D geometry
Overall geometry of the ranger device, such as the centroid of an array of sonar sensors.
Definition: InterfaceDataTypes.idl:843
Definition: InterfaceDataTypes.idl:368
Point2D position
Position of the feature.
Definition: InterfaceDataTypes.idl:569
ActArrayActuatorStatus
Describes the status of an actuator.
Definition: InterfaceDataTypes.idl:74
Time tm
Time stamp.
Definition: InterfaceDataTypes.idl:814
sequence< Waypoint3D > Waypoint3DList
Definition: InterfaceDataTypes.idl:742
Data returned by an inertial navigation system.
Definition: InterfaceDataTypes.idl:404
A line feature.
Definition: InterfaceDataTypes.idl:600
Time timeLimit
Target time to arrive at the waypoint by.
Definition: InterfaceDataTypes.idl:734
sequence< Geometry3D > MulticameraGeometryList
Definition: InterfaceDataTypes.idl:668
Vector in 2D cartesian space.
Definition: ExtendedDataTypes.idl:55
Time since epoch as reported by a GPS device.
Definition: InterfaceDataTypes.idl:312
unsigned long id
Identification number.
Definition: InterfaceDataTypes.idl:262
Point3D point
The position of the point.
Definition: InterfaceDataTypes.idl:767
sequence< double > IntensityList
Definition: InterfaceDataTypes.idl:895
double minRange
Minimum range in metres at which fiducials can be detected.
Definition: InterfaceDataTypes.idl:297
OGMapCells cells
Tile cells in (row, column) order.
Definition: InterfaceDataTypes.idl:557
double panSpeed
Speed at which the pan-tilt unit is changing its pan angle in radians per second. ...
Definition: InterfaceDataTypes.idl:818
double probability
Probability of the feature.
Definition: InterfaceDataTypes.idl:603
Orientation3D orientation
Definition: InterfaceDataTypes.idl:137
double longitude
Longitude in degrees.
Definition: InterfaceDataTypes.idl:411
unsigned long row
Y coordinate of the (0, 0) cell of this tile in the whole map.
Definition: InterfaceDataTypes.idl:551
Stores the current draw of a single actuator.
Definition: InterfaceDataTypes.idl:60
double verticalSpeed
Estimated vertical speed in metres per second.
Definition: InterfaceDataTypes.idl:352
State of a gripper.
Definition: InterfaceDataTypes.idl:376
GPSTime timeFromGPS
GPS time, according to the device.
Definition: InterfaceDataTypes.idl:336
Time-stamped list of localisation hypotheses in 2D space.
Definition: InterfaceDataTypes.idl:476