[openrtm-commit:01362] r120 - in branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration: . idl include/ImageCalibration src
openrtm @ openrtm.org
openrtm @ openrtm.org
2014年 3月 17日 (月) 09:40:14 JST
Author: kawauchi
Date: 2014-03-17 09:40:13 +0900 (Mon, 17 Mar 2014)
New Revision: 120
Added:
branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/CalibrationService.idl
branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/BasicDataType.idl
branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/CalibrationService.idl
branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/ExtendedDataTypes.idl
branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/InterfaceDataTypes.idl
branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/include/ImageCalibration/CalibrationServiceSVC_impl.h
branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/src/CalibrationServiceSVC_impl.cpp
Log:
ImageCalibration : Fixed for rv119. Added new files. refs #2704
Added: branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/CalibrationService.idl
===================================================================
--- branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/CalibrationService.idl (rev 0)
+++ branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/CalibrationService.idl 2014-03-17 00:40:13 UTC (rev 120)
@@ -0,0 +1,22 @@
+#ifndef CALIBRATION_SERVICE_IDL
+#define CALIBRATION_SERVICE_IDL
+
+#include "InterfaceDataTypes.idl"
+
+module ImageCalibService
+{
+ typedef sequence<RTC::CameraImage> ImageList;
+ interface CalibrationService
+ {
+ void setImageNumber(in short num);
+ short getImageNumber();
+ RTC::CameraImage captureCalibImage(in short num);
+ RTC::CameraImage getCalibImage(in short num);
+ ImageList getCalibImages();
+ boolean removeCalibImage(in short num);
+ RTC::CameraInfo getCalibParameter();
+ };
+};
+
+#endif /* CALIBRATION_SERVICE_IDL */
+
Added: branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/BasicDataType.idl
===================================================================
--- branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/BasicDataType.idl (rev 0)
+++ branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/BasicDataType.idl 2014-03-17 00:40:13 UTC (rev 120)
@@ -0,0 +1,189 @@
+// -*- IDL -*-
+/*!
+ * @file DataType.idl
+ * @brief Basic Data Type definition
+ * @date $Date: 2007-01-09 15:36:29 $
+ * @author Noriaki Ando <n-ando at aist.go.jp>
+ *
+ * Copyright (C) 2003-2006
+ * Task-intelligence Research Group,
+ * Intelligent Systems Research Institute,
+ * National Institute of
+ * Advanced Industrial Science and Technology (AIST), Japan
+ * All rights reserved.
+ *
+ * $Id: BasicDataType.idl 1580 2009-12-07 08:54:10Z kurihara $
+ *
+ */
+
+#ifndef BasicDataType_idl
+#define BasicDataType_idl
+
+module RTC {
+ //------------------------------------------------------------
+ // Basic data type definition
+ //------------------------------------------------------------
+ struct Time
+ {
+ unsigned long sec; // sec
+ unsigned long nsec; // nano sec
+ };
+
+ struct TimedState
+ {
+ Time tm;
+ short data;
+ };
+
+ struct TimedShort
+ {
+ Time tm;
+ short data;
+ };
+
+ struct TimedLong
+ {
+ Time tm;
+ long data;
+ };
+
+ struct TimedUShort
+ {
+ Time tm;
+ unsigned short data;
+ };
+
+ struct TimedULong
+ {
+ Time tm;
+ unsigned long data;
+ };
+
+ struct TimedFloat
+ {
+ Time tm;
+ float data;
+ };
+
+ struct TimedDouble
+ {
+ Time tm;
+ double data;
+ };
+
+ struct TimedChar
+ {
+ Time tm;
+ char data;
+ };
+
+ struct TimedWChar
+ {
+ Time tm;
+ wchar data;
+ };
+
+ struct TimedBoolean
+ {
+ Time tm;
+ boolean data;
+ };
+
+ struct TimedOctet
+ {
+ Time tm;
+ octet data;
+ };
+
+ struct TimedString
+ {
+ Time tm;
+ string data;
+ };
+
+
+ struct TimedWString
+ {
+ Time tm;
+ wstring data;
+ };
+
+
+ /*!
+ * Sequence data type
+ */
+ struct TimedShortSeq
+ {
+ Time tm;
+ sequence<short> data;
+ };
+
+ struct TimedLongSeq
+ {
+ Time tm;
+ sequence<long> data;
+ };
+
+ struct TimedUShortSeq
+ {
+ Time tm;
+ sequence<unsigned short> data;
+ };
+
+ struct TimedULongSeq
+ {
+ Time tm;
+ sequence<unsigned long> data;
+ };
+
+ struct TimedFloatSeq
+ {
+ Time tm;
+ sequence<float> data;
+ };
+
+ struct TimedDoubleSeq
+ {
+ Time tm;
+ sequence<double> data;
+ };
+
+ struct TimedCharSeq
+ {
+ Time tm;
+ sequence<char> data;
+ };
+
+ struct TimedWCharSeq
+ {
+ Time tm;
+ sequence<wchar> data;
+ };
+
+ struct TimedBooleanSeq
+ {
+ Time tm;
+ sequence<boolean> data;
+ };
+
+ struct TimedOctetSeq
+ {
+ Time tm;
+ sequence<octet> data;
+ };
+
+ struct TimedStringSeq
+ {
+ Time tm;
+ sequence<string> data;
+ };
+
+ struct TimedWStringSeq
+ {
+ Time tm;
+ sequence<wstring> data;
+ };
+
+};
+
+#endif // end of BasicDataType_idl
Added: branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/CalibrationService.idl
===================================================================
--- branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/CalibrationService.idl (rev 0)
+++ branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/CalibrationService.idl 2014-03-17 00:40:13 UTC (rev 120)
@@ -0,0 +1,22 @@
+#ifndef CALIBRATION_SERVICE_IDL
+#define CALIBRATION_SERVICE_IDL
+
+#include "InterfaceDataTypes.idl"
+
+module ImageCalibService
+{
+ typedef sequence<RTC::CameraImage> ImageList;
+ interface CalibrationService
+ {
+ void setImageNumber(in short num);
+ short getImageNumber();
+ RTC::CameraImage captureCalibImage(in short num);
+ RTC::CameraImage getCalibImage(in short num);
+ ImageList getCalibImages();
+ boolean removeCalibImage(in short num);
+ RTC::CameraInfo getCalibParameter();
+ };
+};
+
+#endif /* CALIBRATION_SERVICE_IDL */
+
Added: branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/ExtendedDataTypes.idl
===================================================================
--- branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/ExtendedDataTypes.idl (rev 0)
+++ branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/ExtendedDataTypes.idl 2014-03-17 00:40:13 UTC (rev 120)
@@ -0,0 +1,699 @@
+// -*- IDL -*-
+/*!
+ * @file ExtendedDataTypes.idl
+ * @brief Extended data types for robotics applications.
+ * @date $Date: $
+ * @author Geoffrey Biggs <geoffrey.biggs at 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;
+ };
+};
+
+#endif // ExtendedDataTypes_idl
Added: branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/InterfaceDataTypes.idl
===================================================================
--- branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/InterfaceDataTypes.idl (rev 0)
+++ branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/idl/InterfaceDataTypes.idl 2014-03-17 00:40:13 UTC (rev 120)
@@ -0,0 +1,923 @@
+// -*- IDL -*-
+/*!
+ * @file InterfaceDataTypes.idl
+ * @brief Interface-specific data types for robot device interfaces.
+ * @date $Date: $
+ * @author Geoffrey Biggs <geoffrey.biggs at 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 InterfaceDataTypes_idl
+#define InterfaceDataTypes_idl
+
+#include "BasicDataType.idl"
+#include "ExtendedDataTypes.idl"
+
+module RTC {
+ //------------------------------------------------------------
+ // ActArray
+ //------------------------------------------------------------
+
+ /*!
+ * @struct ActArrayActuatorPos
+ * @brief Stores the position of a single actuator.
+ */
+ struct ActArrayActuatorPos
+ {
+ /// Time stamp.
+ Time tm;
+ /// Zero-based index of the actuator.
+ unsigned short index;
+ /// Position of the actuator in metres or radians.
+ double position;
+ };
+
+ /*!
+ * @struct ActArrayActuatorSpeed
+ * @brief Stores the speed of a single actuator.
+ */
+ struct ActArrayActuatorSpeed
+ {
+ /// Time stamp.
+ Time tm;
+ /// Zero-based index of the actuator.
+ unsigned short index;
+ /// Speed of the actuator in metres per second or radians per second.
+ double speed;
+ };
+
+ /*!
+ * @struct ActArrayActuatorCurrent
+ * @brief Stores the current draw of a single actuator.
+ */
+ struct ActArrayActuatorCurrent
+ {
+ /// Time stamp.
+ Time tm;
+ /// Zero-based index of the actuator.
+ unsigned short index;
+ /// Current of the actuator in amps.
+ double current;
+ };
+
+ /*!
+ * @enum ActArrayActuatorStatus
+ * @brief Describes the status of an actuator.
+ */
+ enum ActArrayActuatorStatus {ACTUATOR_STATUS_IDLE,
+ ACTUATOR_STATUS_MOVING,
+ ACTUATOR_STATUS_BRAKED,
+ ACTUATOR_STATUS_STALLED};
+
+ /*!
+ * @struct Actuator
+ * @brief State information of a single actuator.
+ */
+ struct Actuator
+ {
+ /// Current position of the actuator, in metres (for linear actuators) or radians (for
+ /// rotary actuators).
+ double position;
+ /// Current speed of the actuator, in metres per second or radians per second.
+ double speed;
+ /// Current acceleration of the actuator, in metres per second or radians per second.
+ double accel;
+ /// Current draw of the actuator, in amps.
+ double current;
+ /// Status of the actuator.
+ ActArrayActuatorStatus status;
+ };
+
+ /*!
+ * @typedef ActuatorList
+ * @brief List of Actuator elements.
+ */
+ typedef sequence<Actuator> ActuatorList;
+ /*!
+ * @struct ActArrayState
+ * @brief State of all actuators in an array.
+ */
+ struct ActArrayState
+ {
+ /// Time stamp.
+ Time tm;
+ /// Sequence of actuator states, one for each actuator.
+ ActuatorList actuators;
+ };
+
+ /*!
+ * @enum ActArrayActuatorType
+ * @brief Describes the type of an actuator.
+ */
+ enum ActArrayActuatorType {ACTARRAY_ACTUATORTYPE_LINEAR,
+ ACTARRAY_ACTUATORTYPE_ROTARY};
+
+ /*!
+ * @struct ActArrayActuatorGeometry
+ * @brief Describes the geometry of an individual actuator.
+ */
+ struct ActArrayActuatorGeometry
+ {
+ /// Type of the actuator.
+ ActArrayActuatorType type;
+ /// Lenght of the actuator's link to the next actuator. For linear actuators, this is the
+ /// length when at 0 position.
+ double length;
+ /// Orientation of the actuator when it is in its rest position. When combined with the
+ /// length of the actuator's link, this will give the position in space of the next actuator
+ /// in the array in the coordinate space of this actuator (i.e. it is the direction to the
+ /// next actuator).
+ Orientation3D orientation;
+ /// The axis of rotation for this actuator if it is rotary, or axis along which it moves if it is linear.
+ Vector3D axis;
+ /// Minimum range of motion of the actuator, in metres or radians.
+ double minRange;
+ /// Centre point of the actuator's range of motion, in metres or radians.
+ double centre;
+ /// Maximum range of motion of the actuator, in metres or radians.
+ double maxRange;
+ /// Home position of the actuator, in metres or radians.
+ double homePosition;
+ /// True if the actuator has brakes.
+ boolean hasBrakes;
+ };
+
+ /*!
+ * @typedef ActArrayActuatorGeometryList
+ * @brief List of ActArrayActuatorGeometry elements.
+ */
+ typedef sequence<ActArrayActuatorGeometry> ActArrayActuatorGeometryList;
+
+ /*!
+ * @struct ActArrayGeometry
+ * @brief Geometry of an actuator array.
+ */
+ struct ActArrayGeometry
+ {
+ /// Geometry of the overall array.
+ Geometry3D arrayGeometry;
+ /// Geometry of the individual actuators.
+ ActArrayActuatorGeometryList actuatorGeometry;
+ };
+
+ //------------------------------------------------------------
+ // Bumper
+ //------------------------------------------------------------
+
+ /*!
+ * @struct BumperGeometry
+ * @brief Geometry of a single bumper.
+ */
+ struct BumperGeometry
+ {
+ /// Pose of the bumper's base point in the array's coordinate space.
+ Pose3D pose;
+ /// Size of the bumper.
+ Size3D size;
+ /// Radius of curvature of the bump sensor in metres. Zero if the bumper is a straight line.
+ double roc;
+ };
+
+ /*!
+ * @typedef BumperGeometryList
+ */
+ typedef sequence<BumperGeometry> BumperGeometryList;
+
+ /*!
+ * @struct BumperArrayGeometry
+ * @brief Geometry of an array of bump sensors.
+ */
+ struct BumperArrayGeometry
+ {
+ /// Geometry of the entire array.
+ Geometry3D arrayGeometry;
+ /// Geometry of each individual bumper.
+ BumperGeometryList bumperGeometry;
+ };
+
+ //------------------------------------------------------------
+ // Camera
+ //------------------------------------------------------------
+
+ /*!
+ * @struct CameraImage
+ * @brief Stores an image from a camera or camera-like device.
+ */
+ struct CameraImage
+ {
+ /// Time stamp.
+ Time tm;
+ /// Image pixel width.
+ unsigned short width;
+ /// Image pixel height.
+ unsigned short height;
+ /// Bits per pixel.
+ unsigned short bpp;
+ /// Image format (e.g. bitmap, jpeg, etc.).
+ string format;
+ /// Scale factor for images, such as disparity maps, where the integer pixel value should be divided by this factor to get the real pixel value.
+ double fDiv;
+ /// Raw pixel data.
+ sequence<octet> pixels;
+ };
+
+ /*!
+ * @struct CameraInfo
+ * @brief Information about an image-producing device.
+ */
+ struct CameraInfo
+ {
+ /// Focal length (x, y) in metres.
+ Vector2D focalLength;
+ /// Principal point of the camera.
+ Point2D principalPoint;
+ /// Radial distortion coefficient 1.
+ double k1;
+ /// Radial distortion coefficient 2.
+ double k2;
+ /// Tangential distortion coefficient 1.
+ double p1;
+ /// Tangential distortion coefficient 2.
+ double p2;
+ };
+
+ //------------------------------------------------------------
+ // Fiducial
+ //------------------------------------------------------------
+
+ /*!
+ * @struct FiducialInfo
+ * @brief Information about a single fiducial.
+ */
+ struct FiducialInfo
+ {
+ /// Identification number.
+ unsigned long id;
+ /// Detected pose.
+ Pose3D pose;
+ /// Uncertainty in the pose.
+ Pose3D poseUncertainty;
+ /// Detected size.
+ Size3D size;
+ /// Uncertainty in the size.
+ Size3D sizeUncertainty;
+ };
+
+ /*!
+ * @typedef FiducialInfoList
+ */
+ typedef sequence<FiducialInfo> FiducialInfoList;
+
+ /*!
+ * @struct Fiducials
+ * @brief Time-stamped list of detected fiducials.
+ */
+ struct Fiducials
+ {
+ /// Time stamp.
+ Time tm;
+ /// List of detected fiducials.
+ FiducialInfoList fiducialsList;
+ };
+
+ /*!
+ * @struct FiducialFOV
+ * @brief Field of view of a fiducial tracker.
+ */
+ struct FiducialFOV
+ {
+ /// Minimum range in metres at which fiducials can be detected.
+ double minRange;
+ /// Maximum range in metres at which fiducials can be detected.
+ double maxRange;
+ /// Receptive angle in radians of the sensor (centred about the forward direction).
+ double viewAngle;
+ };
+
+ //------------------------------------------------------------
+ // GPS
+ //------------------------------------------------------------
+
+ /*!
+ * @struct GPSTime
+ * @brief Time since epoch as reported by a GPS device.
+ */
+ struct GPSTime
+ {
+ /// Seconds value.
+ unsigned long sec;
+ /// Microseconds value.
+ unsigned long msec;
+ };
+
+ /*!
+ * @enum GPSFixType
+ */
+ enum GPSFixType {GPS_FIX_NONE,
+ GPS_FIX_NORMAL,
+ GPS_FIX_DGPS};
+
+ /*!
+ * @struct GPSData
+ * @brief Data as returned by a common GPS device.
+ */
+ struct GPSData
+ {
+ /// Time stamp.
+ Time tm;
+ /// GPS time, according to the device.
+ GPSTime timeFromGPS;
+ /// Latitude in degrees.
+ double latitude;
+ /// Longitude in degrees.
+ double longitude;
+ /// Altitude above the ellisoid in metres.
+ double altitude;
+ /// One standard deviation in the horizontal position error, in metres.
+ double horizontalError;
+ /// One standard deviation in the vertical position error, in metres.
+ double verticalError;
+ /// Estimated heading from true north in radians.
+ double heading;
+ /// Estimated horizontal speed in metres per second.
+ double horizontalSpeed;
+ /// Estimated vertical speed in metres per second.
+ double verticalSpeed;
+ /// Number of satellites in view.
+ unsigned short numSatellites;
+ /// The type of position fix this is.
+ GPSFixType fixType;
+ };
+
+ //------------------------------------------------------------
+ // Gripper
+ //------------------------------------------------------------
+
+ /*!
+ * @enum GripperStatus
+ * @brief Describes the status of a gripper.
+ */
+ enum GripperStatus {GRIPPER_STATE_OPEN,
+ GRIPPER_STATE_CLOSED,
+ GRIPPER_STATE_MOVING,
+ GRIPPER_STATE_UNKNOWN};
+
+ /*!
+ * @struct GripperState
+ * @brief State of a gripper.
+ */
+ struct GripperState
+ {
+ /// Time stamp.
+ Time tm;
+ /// Status of the gripper.
+ GripperStatus status;
+ };
+
+ /*!
+ * @struct GripperGeometry
+ * @brief Geometry of a gripper, including both the outside and inside sizes.
+ */
+ struct GripperGeometry
+ {
+ /// Geometry of the exterior of the gripper when open, in parent coordinate space.
+ Geometry3D exterior;
+ /// Geometry of the interior of the gripper when open, in gripper coordinate space.
+ Geometry3D interior;
+ };
+
+ //------------------------------------------------------------
+ // INS
+ //------------------------------------------------------------
+
+ /*!
+ * @struct INSData
+ * @brief Data returned by an inertial navigation system.
+ */
+ struct INSData
+ {
+ /// Time stamp.
+ Time tm;
+ /// Latitude in degrees.
+ double latitude;
+ /// Longitude in degrees.
+ double longitude;
+ /// Altitude in metres.
+ double altitude;
+ /// Height above mean sea level in metres.
+ double heightAMSL;
+ /// Velocity east/north/up.
+ Velocity3D velocityENU;
+ /// Orientation, where east is 0.
+ Orientation3D orientation;
+ };
+
+ //------------------------------------------------------------
+ // Limb
+ //------------------------------------------------------------
+
+ /*!
+ * @enum LimbStatus
+ */
+ enum LimbStatus {LIMB_STATUS_IDLE,
+ LIMB_STATUS_BRAKED,
+ LIMB_STATUS_MOVING,
+ LIMB_STATUS_OOR,
+ LIMB_STATUS_COLLISION};
+
+ /*!
+ * @struct LimbState
+ * @brief Time-stamped state of a limb.
+ */
+ struct LimbState
+ {
+ /// Time stamp.
+ Time tm;
+ /// Orientation, approach and position of the end-effector.
+ OAP oapMatrix;
+ /// Current status of the limb.
+ LimbStatus status;
+ };
+
+ //------------------------------------------------------------
+ // Localise
+ //------------------------------------------------------------
+
+ /*!
+ * @struct Hypothesis2D
+ * @brief A pose hypothesis in 2D space.
+ */
+ struct Hypothesis2D
+ {
+ /// Mean of the localisation hypothesis.
+ Pose2D mean;
+ /// Covariance matrix of the mean pose.
+ Covariance2D covariance;
+ /// Weight of this hypothesis for mixing.
+ double weight;
+ };
+
+ /*!
+ * @typedef Hypothesis2DList
+ */
+ typedef sequence<Hypothesis2D> Hypothesis2DList;
+
+ /*!
+ * @struct Hypotheses2D
+ * @brief Time-stamped list of localisation hypotheses in 2D space.
+ */
+ struct Hypotheses2D
+ {
+ /// Time stamp.
+ Time tm;
+ /// List of hypotheses.
+ Hypothesis2DList hypotheses;
+ };
+
+ /*!
+ * @struct Hypothesis3D
+ * @brief A pose hypothesis in 3D space.
+ */
+ struct Hypothesis3D
+ {
+ /// Mean of the localisation hypothesis.
+ Pose3D mean;
+ /// Covariance matrix of the mean pose.
+ Covariance3D covariance;
+ /// Weight of this hypothesis for mixing.
+ double weight;
+ };
+
+ /*!
+ * @typedef Hypothesis3DList
+ */
+ typedef sequence<Hypothesis3D> Hypothesis3DList;
+
+ /*!
+ * @struct Hypotheses3D
+ * @brief Time-stamped list of localisation hypotheses in 3D space.
+ */
+ struct Hypotheses3D
+ {
+ /// Time stamp.
+ Time tm;
+ /// List of hypotheses.
+ Hypothesis3DList hypotheses;
+ };
+
+ //------------------------------------------------------------
+ // Map
+ //------------------------------------------------------------
+
+ /*!
+ * @struct OGMapConfig
+ * @brief Configuration of a occupancy-grip map.
+ */
+ struct OGMapConfig
+ {
+ /// Scale on the x axis (metres per cell).
+ double xScale;
+ /// Scale on the y axis (metres per cell).
+ double yScale;
+ /// Number of cells along the x axis.
+ unsigned long width;
+ /// Number of cells along the y axis.
+ unsigned long height;
+ /// Pose of the cell at (0, 0) in the real world.
+ Pose2D origin;
+ };
+
+ /*!
+ * @typedef OGMapCells
+ */
+ typedef sequence<octet> OGMapCells;
+
+ /*!
+ * @struct OGMapTile
+ * @brief A tile from an occupancy-grid map.
+ */
+ struct OGMapTile
+ {
+ /// X coordinate of the (0, 0) cell of this tile in the whole map.
+ unsigned long column;
+ /// Y coordinate of the (0, 0) cell of this tile in the whole map.
+ unsigned long row;
+ /// Number of cells along the x axis in this tile;
+ unsigned long width;
+ /// Number of cells along the y axis in this tile;
+ unsigned long height;
+ /// Tile cells in (row, column) order.
+ OGMapCells cells;
+ };
+
+ /*!
+ * @struct PointFeature
+ * @brief A size-less point feature.
+ */
+ struct PointFeature
+ {
+ /// Probability of the feature.
+ double probability;
+ /// Position of the feature.
+ Point2D position;
+ /// Covariance matrix of the position.
+ PointCovariance2D covariance;
+ };
+ /*!
+ * @typedef PointFeatureList
+ */
+ typedef sequence<PointFeature> PointFeatureList;
+
+ /*!
+ * @struct PoseFeature
+ * @brief A size-less point feature with orientation.
+ */
+ struct PoseFeature
+ {
+ /// Probability of the feature.
+ double probability;
+ /// Pose of the feature.
+ Pose2D position;
+ /// Covariance matrix of the pose.
+ Covariance2D covariance;
+ };
+ /*!
+ * @typedef PoseFeatureList
+ */
+ typedef sequence<PoseFeature> PoseFeatureList;
+
+ /*!
+ * @struct LineFeature
+ * @brief A line feature.
+ */
+ struct LineFeature
+ {
+ /// Probability of the feature.
+ double probability;
+ /// Length of the line vector in metres.
+ double rho;
+ /// Angle of the line vector from the x axis in radians.
+ double alpha;
+ /// Covariance matrix of rho and alpha.
+ PointCovariance2D covariance;
+ /// Start point of the line segment.
+ Point2D start;
+ /// End point of the line segment.
+ Point2D end;
+ /// True if the start point of the line has been sighted (i.e. it is inside seen space).
+ boolean startSighted;
+ /// True if the end point of the line has been sighted (i.e. it is inside seen space).
+ boolean endSighted;
+ };
+ /*!
+ * @typedef LineFeatureList
+ */
+ typedef sequence<LineFeature> LineFeatureList;
+
+ /*!
+ * @struct Features
+ * Set of features in a map.
+ */
+ struct Features
+ {
+ /// Time stamp.
+ Time tm;
+ /// Point features.
+ PointFeatureList pointFeatures;
+ /// Pose features.
+ PoseFeatureList poseFeatures;
+ /// Line features.
+ LineFeatureList lineFeatures;
+ };
+
+ //------------------------------------------------------------
+ // Multicamera
+ //------------------------------------------------------------
+
+ /*!
+ * @typedef MulticameraImageList
+ */
+ typedef sequence<CameraImage> MulticameraImageList;
+ /*!
+ * @struct MulticameraImages
+ * @brief Images from a set of cameras.
+ */
+ struct MultiCameraImages
+ {
+ /// Time stamp.
+ Time tm;
+ /// Image list.
+ MulticameraImageList images;
+ };
+
+ /*!
+ * @typedef MulticameraInfoList
+ */
+ typedef sequence<CameraInfo> MulticameraInfoList;
+
+ /*!
+ * @typedef MulticameraGeometryList
+ */
+ typedef sequence<Geometry3D> MulticameraGeometryList;
+
+ /*!
+ * @struct MulticameraGeometry
+ * @brief Geometry of a multi-camera system, such as a stereo camera.
+ */
+ struct MulticameraGeometry
+ {
+ /// Overall geometry of the camera system.
+ Geometry3D geometry;
+ /// Geometry of each camera.
+ MulticameraGeometryList cameraGeometries;
+ };
+
+ //------------------------------------------------------------
+ // Paths
+ //------------------------------------------------------------
+
+ /*!
+ * @struct Waypoint2D
+ * @brief A waypoint in 2D space, including constraints.
+ */
+ struct Waypoint2D
+ {
+ /// Location of the waypoint.
+ Pose2D target;
+ /// How far away from the waypoint is considered success (radius in metres).
+ double distanceTolerance;
+ /// How much off the target heading is considered success (in radians).
+ double headingTolerance;
+ /// Target time to arrive at the waypoint by.
+ Time timeLimit;
+ /// Maximum sped to travel at while heading to the waypoint.
+ Velocity2D maxSpeed;
+ };
+
+ /*!
+ * @typedef Waypoint2DList
+ */
+ typedef sequence<Waypoint2D> Waypoint2DList;
+
+ /*!
+ * @struct Path2D
+ * @brief A time-stamped path in 2D space.
+ */
+ struct Path2D
+ {
+ /// Time stamp.
+ Time tm;
+ /// The sequence of waypoints that make up the path.
+ Waypoint2DList waypoints;
+ };
+
+ /*!
+ * @struct Waypoint3D
+ * @brief A waypoint in 3D space, including constraints.
+ */
+ struct Waypoint3D
+ {
+ /// Location of the waypoint.
+ Pose3D target;
+ /// How far away from the waypoint is considered success (radius in metres).
+ double distanceTolerance;
+ /// How much off the target heading is considered success (in radians).
+ double headingTolerance;
+ /// Target time to arrive at the waypoint by.
+ Time timeLimit;
+ /// Maximum sped to travel at while heading to the waypoint.
+ Velocity3D maxSpeed;
+ };
+
+ /*!
+ * @typedef Waypoint3DList
+ */
+ typedef sequence<Waypoint3D> Waypoint3DList;
+
+ /*!
+ * @struct Path3D
+ * @brief A time-stamped path in 3D space.
+ */
+ struct Path3D
+ {
+ /// Time stamp.
+ Time tm;
+ /// The sequence of waypoints that make up the path.
+ Waypoint3DList waypoints;
+ };
+
+ //------------------------------------------------------------
+ // PointCloud
+ //------------------------------------------------------------
+
+ /*!
+ * @struct PointCloudPoint
+ * @brief A point in a point cloud.
+ */
+ struct PointCloudPoint
+ {
+ /// The position of the point.
+ Point3D point;
+ /// The colour of the point, if any.
+ RGBColour colour;
+ };
+
+ /*!
+ * @typedef PointCloudPointList
+ */
+ typedef sequence<PointCloudPoint> PointCloudPointList;
+
+ /*!
+ * @struct PointCloud
+ * @brief A cloud of points in 3D space.
+ */
+ struct PointCloud
+ {
+ /// Time stamp.
+ Time tm;
+ /// The points in the cloud.
+ PointCloudPointList points;
+ };
+
+ //------------------------------------------------------------
+ // PanTilt
+ //------------------------------------------------------------
+
+ /*!
+ * @struct PanTiltAngles
+ * @brief Pan and tilt values of a pan-tilt unit.
+ */
+ struct PanTiltAngles
+ {
+ /// Time stamp.
+ Time tm;
+ /// Pan value in radians.
+ double pan;
+ /// Tilt value in radians.
+ double tilt;
+ };
+
+ /*!
+ * @struct PanTiltState
+ * @brief Status of a pan-tilt unit.
+ */
+ struct PanTiltState
+ {
+ /// Time stamp.
+ Time tm;
+ /// Pan and tilt angles.
+ PanTiltAngles angles;
+ /// Speed at which the pan-tilt unit is changing its pan angle in radians per second.
+ double panSpeed;
+ /// Speed at which the pan-tilt unit is changing its tilt angle in radians per second.
+ double tiltSpeed;
+ };
+
+ //------------------------------------------------------------
+ // Ranger
+ //------------------------------------------------------------
+
+ /*!
+ * @typedef ElementGeometryList
+ */
+ typedef sequence<Geometry3D> ElementGeometryList;
+
+ /*!
+ * @struct RangerGeometry
+ * @brief Geometry of a ranger device. A range sensor may be a single device returning multiple
+ * ranges (such as a laser scanner), or an array of sensing elements each returning a single
+ * range value (such as an array of sonar sensors). If there is only one sensing element in the
+ * device, the device should be considered a laser scanner type. If there are multiple
+ * elements, the device should be considered an array of single-range-value sensors.
+ */
+ struct RangerGeometry
+ {
+ /// Overall geometry of the ranger device, such as the centroid of an array of sonar sensors.
+ Geometry3D geometry;
+ /// Geometry of each individual sensing element. The range values should be considered
+ /// measured from each of these.
+ ElementGeometryList elementGeometries;
+ };
+
+ /*!
+ * @struct RangerConfig
+ * @brief The configuration of a ranger device.
+ */
+ struct RangerConfig
+ {
+ /// Minimum scannable angle in radians.
+ double minAngle;
+ /// Maximum scannable angle in radians.
+ double maxAngle;
+ /// Angular resolution in radians.
+ double angularRes;
+ /// Minimum scannable range in metres.
+ double minRange;
+ /// Maximum scannable range in metres.
+ double maxRange;
+ /// Range resolution in metres.
+ double rangeRes;
+ /// Scanning frequency in Hertz.
+ double frequency;
+ };
+
+ /*!
+ * @typedef RangeList
+ */
+ typedef sequence<double> RangeList;
+
+ /*!
+ * @struct RangeData
+ * @brief Range readings from a range sensor.
+ */
+ struct RangeData
+ {
+ /// Time stamp.
+ Time tm;
+ /// Range values in metres.
+ RangeList ranges;
+ /// Geometry of the ranger at the time the scan data was measured.
+ RangerGeometry geometry;
+ /// Configuration of the ranger at the time the scan data was measured.
+ RangerConfig config;
+ };
+
+ /*!
+ * @typedef IntensityList
+ */
+ typedef sequence<double> IntensityList;
+
+ /*!
+ * @struct IntensityData
+ * @brief Intensity readings from a range sensor.
+ */
+ struct IntensityData
+ {
+ /// Time stamp.
+ Time tm;
+ /// Intensity values normalised to between 0 and 1.
+ IntensityList intensities;
+ /// Geometry of the ranger at the time the scan data was measured.
+ RangerGeometry geometry;
+ /// Configuration of the ranger at the time the scan data was measured.
+ RangerConfig config;
+ };
+
+ //------------------------------------------------------------
+ // RFID
+ //------------------------------------------------------------
+
+ /*!
+ * @typedef RFIDTagData
+ */
+ typedef sequence<octet> RFIDTagData;
+};
+
+#endif // InterfaceDataTypes_idl
Added: branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/include/ImageCalibration/CalibrationServiceSVC_impl.h
===================================================================
--- branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/include/ImageCalibration/CalibrationServiceSVC_impl.h (rev 0)
+++ branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/include/ImageCalibration/CalibrationServiceSVC_impl.h 2014-03-17 00:40:13 UTC (rev 120)
@@ -0,0 +1,80 @@
+// -*-C++-*-
+/*!
+ * @file CalibrationServiceSVC_impl.h
+ * @brief Service implementation header of CalibrationService.idl
+ *
+ */
+
+#include "InterfaceDataTypesSkel.h"
+#include "BasicDataTypeSkel.h"
+#include "ExtendedDataTypesSkel.h"
+
+#include "CalibrationServiceSkel.h"
+
+#ifndef CALIBRATIONSERVICESVC_IMPL_H
+#define CALIBRATIONSERVICESVC_IMPL_H
+
+#include <iostream>
+#include <coil/Mutex.h>
+
+/* OpenCVHeadファイルのIncluding */
+#include <cv.h>
+#include <cxcore.h>
+#include <highgui.h>
+
+/*!
+ * @class CalibrationServiceSVC_impl
+ * Example class implementing IDL interface ImageCalibService::CalibrationService
+ */
+class CalibrationServiceSVC_impl
+ : public virtual POA_ImageCalibService::CalibrationService,
+ public virtual PortableServer::RefCountServantBase
+{
+ private:
+ // Make sure all instances are built on the heap by making the
+ // destructor non-public
+ //virtual ~CalibrationServiceSVC_impl();
+
+ public:
+ /*!
+ * @brief standard constructor
+ */
+ CalibrationServiceSVC_impl();
+ /*!
+ * @brief destructor
+ */
+ virtual ~CalibrationServiceSVC_impl();
+
+ // attributes and operations
+ void setImageNumber(CORBA::Short num);
+ CORBA::Short getImageNumber();
+ RTC::CameraImage* captureCalibImage(CORBA::Short num);
+ RTC::CameraImage* getCalibImage(CORBA::Short num);
+ ImageCalibService::ImageList* getCalibImages();
+ CORBA::Boolean removeCalibImage(CORBA::Short num);
+ RTC::CameraInfo getCalibParameter();
+
+ void setCurrentImage(RTC::CameraImage* cameraimage);
+ void setCheckerSize(int width, int height);
+
+ private:
+ CORBA::Boolean removeFile(std::string name);
+ void outUndistortedImage(cv::Mat cameraMatrix, cv::Mat distCoeffs);
+ void outYamlFile(cv::Mat cameraMatrix, cv::Mat distCoeffs);
+ std::string getSavePath();
+
+ ImageCalibService::ImageList m_imageList;
+ RTC::CameraImage m_currentCameraImg;
+ coil::Mutex m_mutex;
+ CORBA::Short m_current_image_num; /* チェスボード撮影枚数 */
+ CORBA::Short m_old_image_num; /* 変更前のチェスボード撮影枚数 */
+ int m_checker_w; /* チェスボード横方向の交点の数 */
+ int m_checker_h; /* チェスボード縦方向の交点の数 */
+ std::string m_cap_filename;
+};
+
+
+
+#endif // CALIBRATIONSERVICESVC_IMPL_H
+
+
Added: branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/src/CalibrationServiceSVC_impl.cpp
===================================================================
--- branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/src/CalibrationServiceSVC_impl.cpp (rev 0)
+++ branches/newCMakeForVC2010/ImageProcessing/opencv/components/ImageCalibration/src/CalibrationServiceSVC_impl.cpp 2014-03-17 00:40:13 UTC (rev 120)
@@ -0,0 +1,306 @@
+// -*-C++-*-
+/*!
+ * @file CalibrationServiceSVC_impl.cpp
+ * @brief Service implementation code of CalibrationService.idl
+ *
+ */
+
+#include <time.h>
+#include "CalibrationServiceSVC_impl.h"
+#include <rtm/CORBA_SeqUtil.h>
+
+/*
+ * Example implementational code for IDL interface ImageCalibService::CalibrationService
+ */
+CalibrationServiceSVC_impl::CalibrationServiceSVC_impl()
+ :m_imageList(0)
+{
+ m_current_image_num = 0;
+ m_old_image_num = 0;
+}
+
+
+CalibrationServiceSVC_impl::~CalibrationServiceSVC_impl()
+{
+ // Please add extra destructor code here.
+}
+
+
+/*
+ * Methods corresponding to IDL attributes and operations
+ */
+void CalibrationServiceSVC_impl::setImageNumber(CORBA::Short num)
+{
+ m_old_image_num = m_current_image_num;
+ m_current_image_num = num;
+ if(m_old_image_num != 0 && m_old_image_num != m_current_image_num)
+ {
+ /* 保存画像を削除してGUI再描画 */
+ std::cout << "setImageNumber : m_old_image_num = " << m_old_image_num << std::endl;
+ std::cout << "setImageNumber : m_current_image_num = " << m_current_image_num << std::endl;
+ removeCalibImage(-1);
+ }
+ return;
+}
+
+CORBA::Short CalibrationServiceSVC_impl::getImageNumber()
+{
+ m_mutex.lock();
+ CORBA::Short ret_num = m_current_image_num;
+ m_mutex.unlock();
+
+ return ret_num;
+}
+
+RTC::CameraImage* CalibrationServiceSVC_impl::captureCalibImage(CORBA::Short num)
+{
+ cv::Mat frame;
+ std::string filename = "capture";
+ std::ostringstream oss;
+ RTC::CameraImage_var vl;
+
+ m_mutex.lock();
+ vl = new RTC::CameraImage(m_currentCameraImg);
+ frame.create(m_currentCameraImg.height, m_currentCameraImg.width, CV_8UC1);
+ memcpy(frame.data,(void *)&(m_currentCameraImg.pixels[0]), m_currentCameraImg.pixels.length());
+
+ CORBA::ULong len(m_imageList.length());
+ if(len != (CORBA::ULong)m_current_image_num)
+ {
+ m_imageList.length(m_current_image_num);
+ }
+ m_imageList[num] = m_currentCameraImg;
+ m_mutex.unlock();
+
+ filename = getSavePath() + filename;
+ oss << filename << num << ".jpg";
+ cv::imwrite(oss.str(), frame);
+ return vl._retn();
+}
+
+RTC::CameraImage* CalibrationServiceSVC_impl::getCalibImage(CORBA::Short num)
+{
+ ImageCalibService::ImageList_var list;
+ RTC::CameraImage_var image;
+ list = new ImageCalibService::ImageList(m_imageList);
+ image = new RTC::CameraImage(list[num]);
+
+ return image._retn();
+}
+
+ImageCalibService::ImageList* CalibrationServiceSVC_impl::getCalibImages()
+{
+ ImageCalibService::ImageList_var list;
+ list = new ImageCalibService::ImageList(m_imageList);
+
+ return list._retn();
+}
+
+CORBA::Boolean CalibrationServiceSVC_impl::removeCalibImage(CORBA::Short num)
+{
+ std::string filename = "capture";
+ std::ostringstream oss;
+ CORBA::Boolean ret = true;
+
+ filename = getSavePath() + filename;
+
+ if(num == -1)
+ {
+ /* 全画像削除 */
+ m_mutex.lock();
+ CORBA::ULong len(m_imageList.length());
+ CORBA_SeqUtil::clear(m_imageList);
+
+ for(int i=0; i<(CORBA::Short)len; i++)
+ {
+ oss.str("");
+ oss << filename << i << ".jpg";
+ removeFile(oss.str());
+ }
+ m_mutex.unlock();
+ }
+ else
+ {
+ /* 個別削除の場合は、インデックスを詰めないのでメモリ上のデータはそのまま
+ * 指定されたインデックスの画像ファイルのみ削除する
+ */
+ oss << filename << num << ".jpg";
+ ret = removeFile(oss.str());
+ }
+
+ return ret;
+}
+
+RTC::CameraInfo CalibrationServiceSVC_impl::getCalibParameter()
+{
+ int i,j;
+ RTC::CameraInfo cameraInfo = {{0.0},{0.0},0.0};
+ cv::Mat gray;
+ RTC::CameraImage image;
+ /* チェッカー交点座標を格納する行列 */
+ cv::vector<cv::vector<cv::Point2f> > imagePoints(m_current_image_num);
+
+ /* チェッカー交点座標と対応する世界座標の値を格納する行列 */
+ cv::vector<cv::vector<cv::Point3f> > worldPoints(m_current_image_num);
+
+ /* カメラパラメータ行列 */
+ cv::Mat cameraMatrix;
+ cv::Mat distCoeffs;
+ cv::vector<cv::Mat> rotationVectors;
+ cv::vector<cv::Mat> translationVectors;
+
+ /* コーナー位置高精度化のための繰り返し処理の停止基準
+ * 「反復回数が20回に達する」または「イプシロンが0.001に達する」どちらかの条件を満たした時に終了する
+ */
+ cv::TermCriteria criteria( CV_TERMCRIT_ITER | CV_TERMCRIT_EPS, 20, 0.001 );
+
+ /* 保存されている画像枚数チェック */
+
+ CORBA::ULong len(m_imageList.length());
+ if((CORBA::Short)len != m_current_image_num)
+ {
+ /* 指定枚数の画像が保存されていないのでカメラパラメータは算出しない */
+ std::cout << "getCalibParameter : error(image missing)" << std::endl;
+ return cameraInfo;
+ }
+
+ /* チェッカーパターンの交点検出 */
+ for( i = 0; i < m_current_image_num; i++ )
+ {
+ image = m_imageList[i];
+ gray.create(image.height, image.width, CV_8UC1);
+ memcpy(gray.data,(void *)&(image.pixels[0]), image.pixels.length());
+ if(cv::findChessboardCorners(gray, cv::Size(m_checker_w, m_checker_h), imagePoints[i]))
+ {
+// std::cout << " ... All corners found." << std::endl;
+ } else {
+ std::cout << " ... at least 1 corner not found." << std::endl;
+ return cameraInfo;
+ }
+ /* コーナー位置を高精度化 */
+ cv::cornerSubPix(gray, imagePoints[i], cv::Size(11,11), cv::Size(-1,-1), criteria );
+ }
+
+ /* 世界座標を決める */
+ for(i = 0; i < m_current_image_num; i++)
+ {
+ for(j = 0 ; j < cv::Size(m_checker_w, m_checker_h).area(); j++)
+ {
+ worldPoints[i].push_back(cv::Point3f(static_cast<float>( j % m_checker_w * 10),
+ static_cast<float>(j / m_checker_w * 10), 0.0));
+ }
+ }
+
+ /* カメラパラメータ算出 */
+ cv::calibrateCamera( worldPoints, imagePoints, cv::Size(image.width, image.height), cameraMatrix,
+ distCoeffs, rotationVectors, translationVectors );
+
+ cameraInfo.focalLength.x = cameraMatrix.at<double>(0,0);
+ cameraInfo.focalLength.y = cameraMatrix.at<double>(1,1);
+ cameraInfo.principalPoint.x = cameraMatrix.at<double>(0,2);
+ cameraInfo.principalPoint.y = cameraMatrix.at<double>(1,2);
+ cameraInfo.k1 = distCoeffs.at<double>(0);
+ cameraInfo.k2 = distCoeffs.at<double>(1);
+ cameraInfo.p1 = distCoeffs.at<double>(2);
+ cameraInfo.p2 = distCoeffs.at<double>(3);
+
+ /* 歪み補正した画像を出力 */
+ outUndistortedImage(cameraMatrix, distCoeffs);
+
+ /* yamlファイル出力 */
+ outYamlFile(cameraMatrix, distCoeffs);
+
+ return cameraInfo;
+}
+
+void CalibrationServiceSVC_impl::setCurrentImage(RTC::CameraImage* cameraimage)
+{
+ int len = cameraimage->pixels.length();
+ m_currentCameraImg.pixels.length(len);
+ m_currentCameraImg.width = cameraimage->width;
+ m_currentCameraImg.height = cameraimage->height;
+ memcpy((void *)&(m_currentCameraImg.pixels[0]), (void*)&(cameraimage->pixels[0]), len);
+}
+
+void CalibrationServiceSVC_impl::setCheckerSize(int width, int height)
+{
+ m_checker_w = width;
+ m_checker_h = height;
+}
+
+CORBA::Boolean CalibrationServiceSVC_impl::removeFile(std::string name)
+{
+ std::cout << "removeFile : " << name.c_str() << std::endl;
+ if(remove(name.c_str()) != 0)
+ {
+ std::cout << "removeFile : error(file remove) : " << name.c_str() << std::endl;
+ return false;
+ }
+ return true;
+}
+
+void CalibrationServiceSVC_impl::outUndistortedImage(
+ cv::Mat cameraMatrix, cv::Mat distCoeffs)
+{
+ cv::Mat gray, undistorted;
+ std::string filename = "undistorted";
+ std::ostringstream oss;
+ RTC::CameraImage image;
+
+ filename = getSavePath() + filename;
+
+ for(int i = 0; i < m_current_image_num; i++ )
+ {
+ image = m_imageList[i];
+ gray.create(image.height, image.width, CV_8UC1);
+ memcpy(gray.data,(void *)&(image.pixels[0]), image.pixels.length());
+ cv::undistort(gray, undistorted, cameraMatrix, distCoeffs);
+ oss.str("");
+ oss << filename << i << ".jpg";
+ cv::imwrite(oss.str(), undistorted);
+ }
+
+ return;
+}
+
+void CalibrationServiceSVC_impl::outYamlFile(
+ cv::Mat cameraMatrix, cv::Mat distCoeffs)
+{
+ cv::FileStorage fs("camera.yml", cv::FileStorage::WRITE);
+ time_t rawtime; time(&rawtime);
+ fs << "calibration_time" << asctime(localtime(&rawtime));
+ fs << "image_width" << m_imageList[0].width;
+ fs << "image_height" << m_imageList[0].height;
+ fs << "board_width" << m_checker_w;
+ fs << "board_height" << m_checker_h;
+ fs << "cameraMatrix" << cameraMatrix << "distCoeffs" << distCoeffs;
+ fs.release();
+
+ return;
+}
+
+std::string CalibrationServiceSVC_impl::getSavePath()
+{
+ std::string path;
+
+#ifdef WIN32
+ char* strenv;
+ if((strenv = getenv("TEMP")) != NULL || (strenv = getenv("TMP")) != NULL)
+ {
+ path = strenv;
+ path += "\\";
+ }else{
+ path = "c:\\tmp\\";
+ }
+#else
+ path = "/tmp/";
+#endif
+
+ std::cout << "getEnvironTmpPath : " << path.c_str() << std::endl;
+ return path;
+}
+
+// End of example implementational code
+
+
+
More information about the openrtm-commit
mailing list