VirtualRangeCam.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_VIRTUALRANGECAM_H__
00024 #define __IPA_VIRTUALRANGECAM_H__
00025 
00026 #include "StdAfx.h"
00027 
00028 #ifdef __LINUX__
00029         #include <cob_camera_sensors/AbstractRangeImagingSensor.h>
00030 #else
00031         #include <cob_driver/cob_camera_sensors/common/include/cob_camera_sensors/AbstractRangeImagingSensor.h>
00032 #endif
00033 
00034 #include <stdio.h>
00035 #include <math.h>
00036 #include <assert.h>
00037 #include <sstream>
00038 
00039 #include <boost/filesystem.hpp>
00040 
00041 namespace ipa_CameraSensors {
00042 
00043 static const int SWISSRANGER_COLUMNS = 176;
00044 static const int SWISSRANGER_ROWS = 144;
00045 
00050 class __DLL_LIBCAMERASENSORS__ VirtualRangeCam : public AbstractRangeImagingSensor
00051 {
00052 public:
00053 
00054         VirtualRangeCam();
00055         ~VirtualRangeCam();
00056 
00057         //*******************************************************************************
00058         // AbstractRangeImagingSensor interface implementation
00059         //*******************************************************************************
00060 
00061         unsigned long Init(std::string directory, int cameraIndex = 0);
00062 
00063         unsigned long Open();
00064         unsigned long Close();
00065 
00066         unsigned long SetProperty(t_cameraProperty* cameraProperty);
00067         unsigned long SetPropertyDefaults();
00068         unsigned long GetProperty(t_cameraProperty* cameraProperty);
00069 
00070         unsigned long AcquireImages(int widthStepRange, int widthStepGray, int widthStepCartesian, char* rangeImage=NULL, char* intensityImage=NULL,
00071                 char* cartesianImage=NULL, bool getLatestFrame=true, bool undistort=true,
00072                 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1);
00073         unsigned long AcquireImages(cv::Mat* rangeImage = 0, cv::Mat* intensityImage = 0,
00074                 cv::Mat* cartesianImage = 0, bool getLatestFrame = true, bool undistort = true,
00075                 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1);
00076 
00077         unsigned long GetCalibratedUV(double x, double y, double z, double& u, double& v);
00078 
00079         unsigned long SaveParameters(const char* filename);
00080 
00081         bool isInitialized() {return m_initialized;}
00082         bool isOpen() {return m_open;}
00083 
00086         int GetNumberOfImages();
00087 
00092         unsigned long SetPathToImages(std::string path);
00093 
00094 private:
00095         //*******************************************************************************
00096         // Camera specific members
00097         //*******************************************************************************
00098 
00101         inline void UpdateImageDimensionsOnFirstImage(std::string filename, std::string ext=".xml");
00102 
00107         inline void FindSourceImageFormat(std::map<std::string, int>::iterator& itCounter, std::string& ext);
00108 
00109         unsigned long GetCalibratedZMatlab(int u, int v, float zRaw, float& zCalibrated);
00110         unsigned long GetCalibratedXYMatlab(int u, int v, float z, float& x, float& y);
00111 
00117         unsigned long LoadParameters(const char* filename, int cameraIndex);
00118 
00119         bool m_CoeffsInitialized;
00120 
00125         cv::Mat m_CoeffsA0; 
00126         cv::Mat m_CoeffsA1; 
00127         cv::Mat m_CoeffsA2; 
00128         cv::Mat m_CoeffsA3; 
00129         cv::Mat m_CoeffsA4; 
00130         cv::Mat m_CoeffsA5; 
00131         cv::Mat m_CoeffsA6; 
00132 
00133         std::string m_CameraDataDirectory; 
00134         int m_CameraIndex; 
00135 
00136         std::vector<std::string> m_AmplitudeImageFileNames;
00137         std::vector<std::string> m_IntensityImageFileNames;
00138         std::vector<std::string> m_RangeImageFileNames ;
00139         std::vector<std::string> m_CoordinateImageFileNames ;
00140 
00141         int m_ImageWidth;  
00142         int m_ImageHeight; 
00143 
00144         double m_k1, m_k2, m_p1, m_p2; 
00145 };
00146 
00149 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_VirtualCam();
00150 
00151 } // end namespace ipa_CameraSensors
00152 #endif // __IPA_VIRTUALRANGECAM_H__
00153 
00154 


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