AbstractRangeImagingSensor.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00022 
00023 #ifndef __IPA_ABSTRACTRANGEIMAGINGSENSOR_H__
00024 #define __IPA_ABSTRACTRANGEIMAGINGSENSOR_H__
00025 
00026 #include "StdAfx.h"
00027 
00028 #ifdef __LINUX__
00029         #include "cob_vision_utils/CameraSensorDefines.h"
00030         #include "cob_vision_utils/CameraSensorTypes.h"
00031 #else
00032         #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/CameraSensorDefines.h"
00033         #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/CameraSensorTypes.h"
00034 #endif
00035 
00036 #include <opencv/cv.h>
00037 
00038 #include <iostream>
00039 #include <limits>
00040 #include <vector>
00041 
00042 #include <boost/shared_ptr.hpp>
00043 
00044 namespace ipa_CameraSensors {
00045 
00047 class AbstractRangeImagingSensor;
00048 typedef boost::shared_ptr<AbstractRangeImagingSensor> AbstractRangeImagingSensorPtr;
00049 
00052 class __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensor
00053 {
00054 public:
00055 
00058         struct t_RangeCameraParameters
00059         {
00060                 ipa_CameraSensors::t_cameraRole m_CameraRole;   
00061                 std::stringstream m_AmplitudeThreshold;         
00062 
00063                 std::stringstream m_IntegrationTime;            
00064                 std::stringstream m_ModulationFrequency;        
00065                 std::stringstream m_AcquireMode;                        
00066                 std::stringstream m_ExposureMode;                       
00067                 std::stringstream m_DistanceOffset;                     
00068                 std::stringstream m_ROI;                                        
00069                 std::stringstream m_LensCalibration;            
00070 
00071                 std::stringstream m_Interface;                          
00072                 std::stringstream m_IP;                                         
00073         };
00074 
00076         virtual ~AbstractRangeImagingSensor();
00077 
00083         virtual unsigned long Init(std::string directory, int cameraIndex = 0) = 0;
00084 
00089         virtual unsigned long Open() = 0;
00090 
00093         virtual unsigned long Close() = 0;
00094 
00099         virtual unsigned long SetProperty(t_cameraProperty* cameraProperty) =0;
00100 
00103         virtual unsigned long SetPropertyDefaults() =0;
00104 
00109         virtual unsigned long GetProperty(t_cameraProperty* cameraProperty) =0;
00110 
00121         virtual unsigned long AcquireImages(cv::Mat* rangeImage = 0, cv::Mat* intensityImage = 0,
00122                 cv::Mat* cartesianImage = 0, bool getLatestFrame=true, bool undistort=true,
00123                 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1) = 0;
00124 
00137         virtual unsigned long AcquireImages(int widthStepRange, int widthStepGray, int widthStepCartesian, char* rangeImage=NULL, char* grayImage=NULL,
00138                 char* cartesianImage=NULL, bool getLatestFrame=true, bool undistort=true,
00139                 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1) = 0;
00140 
00145         virtual unsigned long SaveParameters(const char* filename) = 0;
00146 
00149         virtual bool isInitialized() = 0;
00150 
00153         virtual bool isOpen() = 0;
00154 
00158         virtual t_CalibrationMethod GetCalibrationMethod() {return m_CalibrationMethod;}
00159 
00162         virtual t_cameraType GetCameraType() {return m_CameraType;}
00163 
00172         virtual unsigned long SetIntrinsics(cv::Mat& intrinsicMatrix,
00173                 cv::Mat& undistortMapX, cv::Mat& undistortMapY);
00174 
00177         virtual int GetNumberOfImages() {return std::numeric_limits<int>::max();};
00178 
00183         virtual unsigned long SetPathToImages(std::string path);
00184 
00185         unsigned int m_ImageCounter; 
00186 
00187 protected:
00188 
00189         t_CalibrationMethod m_CalibrationMethod; 
00190         t_RangeCameraParameters m_RangeCameraParameters; 
00191         t_cameraType m_CameraType; 
00192 
00193         bool m_initialized; 
00194         bool m_open;            
00195 
00196         unsigned int m_BufferSize; 
00197 
00198         cv::Mat m_intrinsicMatrix;              
00199         cv::Mat m_undistortMapX;                
00200         cv::Mat m_undistortMapY;                
00201 
00202 private:
00203 
00209         virtual unsigned long LoadParameters(const char* filename, int cameraIndex) = 0;
00210 };
00211 
00214 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_VirtualCam();
00215 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_Swissranger();
00216 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_PMDCam();
00217 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_Kinect();
00218 
00219 } // end namespace ipa_CameraSensors
00220 #endif // __IPA_ABSTRACTRANGEIMAGINGSENSOR_H__
00221 


cob_camera_sensors
Author(s): Jan Fischer , Richard Bormann
autogenerated on Sat Jun 8 2019 21:02:02