00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00058
00059 #ifndef __IPA_ABSTRACTRANGEIMAGINGSENSOR_H__
00060 #define __IPA_ABSTRACTRANGEIMAGINGSENSOR_H__
00061
00062 #ifdef __LINUX__
00063 #include "cob_vision_utils/CameraSensorDefines.h"
00064
00065 #include "tinyxml/tinyxml.h"
00066
00067 #include "cob_vision_utils/VisionUtils.h"
00068 #include "cob_vision_utils/CameraSensorTypes.h"
00069 #else
00070 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/CameraSensorDefines.h"
00071
00072 #include "cob_vision/windows/src/extern/TinyXml/tinyxml.h"
00073
00074 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/VisionUtils.h"
00075 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/CameraSensorTypes.h"
00076 #endif
00077
00078 #include <iostream>
00079 #include <limits>
00080 #include <vector>
00081
00082 #include <boost/shared_ptr.hpp>
00083
00084 namespace ipa_CameraSensors {
00085
00087 class AbstractRangeImagingSensor;
00088 typedef boost::shared_ptr<AbstractRangeImagingSensor> AbstractRangeImagingSensorPtr;
00089
00092 class __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensor
00093 {
00094 public:
00095
00098 struct t_RangeCameraParameters
00099 {
00100 ipa_CameraSensors::t_cameraRole m_CameraRole;
00101 std::stringstream m_AmplitudeThreshold;
00102
00103 std::stringstream m_IntegrationTime;
00104 std::stringstream m_ModulationFrequency;
00105 std::stringstream m_AcquireMode;
00106 std::stringstream m_ExposureMode;
00107 std::stringstream m_DistanceOffset;
00108 std::stringstream m_ROI;
00109 std::stringstream m_LensCalibration;
00110
00111 std::stringstream m_Interface;
00112 std::stringstream m_IP;
00113 };
00114
00116 virtual ~AbstractRangeImagingSensor();
00117
00123 virtual unsigned long Init(std::string directory, int cameraIndex = 0) = 0;
00124
00129 virtual unsigned long Open() = 0;
00130
00133 virtual unsigned long Close() = 0;
00134
00139 virtual unsigned long SetProperty(t_cameraProperty* cameraProperty) =0;
00140
00143 virtual unsigned long SetPropertyDefaults() =0;
00144
00149 virtual unsigned long GetProperty(t_cameraProperty* cameraProperty) =0;
00150
00161 virtual unsigned long AcquireImages(cv::Mat* rangeImage = 0, cv::Mat* intensityImage = 0,
00162 cv::Mat* cartesianImage = 0, bool getLatestFrame=true, bool undistort=true,
00163 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1) = 0;
00164
00177 virtual unsigned long AcquireImages(int widthStepRange, int widthStepGray, int widthStepCartesian, char* rangeImage=NULL, char* grayImage=NULL,
00178 char* cartesianImage=NULL, bool getLatestFrame=true, bool undistort=true,
00179 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1) = 0;
00180
00185 virtual unsigned long SaveParameters(const char* filename) = 0;
00186
00189 virtual bool isInitialized() = 0;
00190
00193 virtual bool isOpen() = 0;
00194
00198 virtual t_CalibrationMethod GetCalibrationMethod() {return m_CalibrationMethod;}
00199
00202 virtual t_cameraType GetCameraType() {return m_CameraType;}
00203
00212 virtual unsigned long SetIntrinsics(cv::Mat& intrinsicMatrix,
00213 cv::Mat& undistortMapX, cv::Mat& undistortMapY);
00214
00217 virtual int GetNumberOfImages() {return std::numeric_limits<int>::max();};
00218
00223 virtual unsigned long SetPathToImages(std::string path) {return ipa_Utils::RET_OK;};
00224
00225 unsigned int m_ImageCounter;
00226
00227 protected:
00228
00229 t_CalibrationMethod m_CalibrationMethod;
00230 t_RangeCameraParameters m_RangeCameraParameters;
00231 t_cameraType m_CameraType;
00232
00233 bool m_initialized;
00234 bool m_open;
00235
00236 unsigned int m_BufferSize;
00237
00238 cv::Mat m_intrinsicMatrix;
00239 cv::Mat m_undistortMapX;
00240 cv::Mat m_undistortMapY;
00241
00242 private:
00243
00249 virtual unsigned long LoadParameters(const char* filename, int cameraIndex) = 0;
00250 };
00251
00254 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_VirtualCam();
00255 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_Swissranger();
00256 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_PMDCam();
00257 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_Kinect();
00258
00259 }
00260 #endif // __IPA_ABSTRACTRANGEIMAGINGSENSOR_H__
00261