Go to the documentation of this file.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 #include "StdAfx.h"
00063
00064 #ifdef __LINUX__
00065 #include "cob_vision_utils/CameraSensorDefines.h"
00066 #include "cob_vision_utils/CameraSensorTypes.h"
00067 #else
00068 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/CameraSensorDefines.h"
00069 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/CameraSensorTypes.h"
00070 #endif
00071
00072 #include <opencv/cv.h>
00073
00074 #include <iostream>
00075 #include <limits>
00076 #include <vector>
00077
00078 #include <boost/shared_ptr.hpp>
00079
00080 namespace ipa_CameraSensors {
00081
00083 class AbstractRangeImagingSensor;
00084 typedef boost::shared_ptr<AbstractRangeImagingSensor> AbstractRangeImagingSensorPtr;
00085
00088 class __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensor
00089 {
00090 public:
00091
00094 struct t_RangeCameraParameters
00095 {
00096 ipa_CameraSensors::t_cameraRole m_CameraRole;
00097 std::stringstream m_AmplitudeThreshold;
00098
00099 std::stringstream m_IntegrationTime;
00100 std::stringstream m_ModulationFrequency;
00101 std::stringstream m_AcquireMode;
00102 std::stringstream m_ExposureMode;
00103 std::stringstream m_DistanceOffset;
00104 std::stringstream m_ROI;
00105 std::stringstream m_LensCalibration;
00106
00107 std::stringstream m_Interface;
00108 std::stringstream m_IP;
00109 };
00110
00112 virtual ~AbstractRangeImagingSensor();
00113
00119 virtual unsigned long Init(std::string directory, int cameraIndex = 0) = 0;
00120
00125 virtual unsigned long Open() = 0;
00126
00129 virtual unsigned long Close() = 0;
00130
00135 virtual unsigned long SetProperty(t_cameraProperty* cameraProperty) =0;
00136
00139 virtual unsigned long SetPropertyDefaults() =0;
00140
00145 virtual unsigned long GetProperty(t_cameraProperty* cameraProperty) =0;
00146
00157 virtual unsigned long AcquireImages(cv::Mat* rangeImage = 0, cv::Mat* intensityImage = 0,
00158 cv::Mat* cartesianImage = 0, bool getLatestFrame=true, bool undistort=true,
00159 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1) = 0;
00160
00173 virtual unsigned long AcquireImages(int widthStepRange, int widthStepGray, int widthStepCartesian, char* rangeImage=NULL, char* grayImage=NULL,
00174 char* cartesianImage=NULL, bool getLatestFrame=true, bool undistort=true,
00175 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1) = 0;
00176
00181 virtual unsigned long SaveParameters(const char* filename) = 0;
00182
00185 virtual bool isInitialized() = 0;
00186
00189 virtual bool isOpen() = 0;
00190
00194 virtual t_CalibrationMethod GetCalibrationMethod() {return m_CalibrationMethod;}
00195
00198 virtual t_cameraType GetCameraType() {return m_CameraType;}
00199
00208 virtual unsigned long SetIntrinsics(cv::Mat& intrinsicMatrix,
00209 cv::Mat& undistortMapX, cv::Mat& undistortMapY);
00210
00213 virtual int GetNumberOfImages() {return std::numeric_limits<int>::max();};
00214
00219 virtual unsigned long SetPathToImages(std::string path);
00220
00221 unsigned int m_ImageCounter;
00222
00223 protected:
00224
00225 t_CalibrationMethod m_CalibrationMethod;
00226 t_RangeCameraParameters m_RangeCameraParameters;
00227 t_cameraType m_CameraType;
00228
00229 bool m_initialized;
00230 bool m_open;
00231
00232 unsigned int m_BufferSize;
00233
00234 cv::Mat m_intrinsicMatrix;
00235 cv::Mat m_undistortMapX;
00236 cv::Mat m_undistortMapY;
00237
00238 private:
00239
00245 virtual unsigned long LoadParameters(const char* filename, int cameraIndex) = 0;
00246 };
00247
00250 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_VirtualCam();
00251 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_Swissranger();
00252 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_PMDCam();
00253 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_Kinect();
00254
00255 }
00256 #endif // __IPA_ABSTRACTRANGEIMAGINGSENSOR_H__
00257