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