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_VIRTUALRANGECAM_H__
00060 #define __IPA_VIRTUALRANGECAM_H__
00061
00062 #ifdef __LINUX__
00063 #include <cob_camera_sensors/AbstractRangeImagingSensor.h>
00064 #else
00065 #include <cob_driver/cob_camera_sensors/common/include/cob_camera_sensors/AbstractRangeImagingSensor.h>
00066 #endif
00067
00068 #include <stdio.h>
00069 #include <math.h>
00070 #include <assert.h>
00071 #include <sstream>
00072
00073 #include <boost/filesystem.hpp>
00074
00075 #ifdef SWIG
00076 %module Sensors3D
00077
00078 %{
00079 #include "Swissranger.h"
00080 %}
00081 #endif
00082
00083 namespace fs = boost::filesystem;
00084 using namespace ipa_Utils;
00085
00086 namespace ipa_CameraSensors {
00087
00088 static const int SWISSRANGER_COLUMNS = 176;
00089 static const int SWISSRANGER_ROWS = 144;
00090
00095 class __DLL_LIBCAMERASENSORS__ VirtualRangeCam : public AbstractRangeImagingSensor
00096 {
00097 public:
00098
00099 VirtualRangeCam();
00100 ~VirtualRangeCam();
00101
00102
00103
00104
00105
00106 unsigned long Init(std::string directory, int cameraIndex = 0);
00107
00108 unsigned long Open();
00109 unsigned long Close();
00110
00111 unsigned long SetProperty(t_cameraProperty* cameraProperty);
00112 unsigned long SetPropertyDefaults();
00113 unsigned long GetProperty(t_cameraProperty* cameraProperty);
00114
00115 unsigned long AcquireImages(int widthStepRange, int widthStepGray, int widthStepCartesian, char* rangeImage=NULL, char* intensityImage=NULL,
00116 char* cartesianImage=NULL, bool getLatestFrame=true, bool undistort=true,
00117 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1);
00118 unsigned long AcquireImages(cv::Mat* rangeImage = 0, cv::Mat* intensityImage = 0,
00119 cv::Mat* cartesianImage = 0, bool getLatestFrame = true, bool undistort = true,
00120 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1);
00121
00122 unsigned long GetCalibratedUV(double x, double y, double z, double& u, double& v);
00123
00124 unsigned long SaveParameters(const char* filename);
00125
00126 bool isInitialized() {return m_initialized;}
00127 bool isOpen() {return m_open;}
00128
00131 int GetNumberOfImages();
00132
00137 unsigned long SetPathToImages(std::string path);
00138
00139 private:
00140
00141
00142
00143
00146 inline void UpdateImageDimensionsOnFirstImage(std::string filename, std::string ext=".xml");
00147
00152 inline void FindSourceImageFormat(std::map<std::string, int>::iterator& itCounter, std::string& ext);
00153
00154 unsigned long GetCalibratedZMatlab(int u, int v, float zRaw, float& zCalibrated);
00155 unsigned long GetCalibratedXYMatlab(int u, int v, float z, float& x, float& y);
00156
00162 unsigned long LoadParameters(const char* filename, int cameraIndex);
00163
00164 bool m_CoeffsInitialized;
00165
00170 cv::Mat m_CoeffsA0;
00171 cv::Mat m_CoeffsA1;
00172 cv::Mat m_CoeffsA2;
00173 cv::Mat m_CoeffsA3;
00174 cv::Mat m_CoeffsA4;
00175 cv::Mat m_CoeffsA5;
00176 cv::Mat m_CoeffsA6;
00177
00178 std::string m_CameraDataDirectory;
00179 int m_CameraIndex;
00180
00181 std::vector<std::string> m_AmplitudeImageFileNames;
00182 std::vector<std::string> m_IntensityImageFileNames;
00183 std::vector<std::string> m_RangeImageFileNames ;
00184 std::vector<std::string> m_CoordinateImageFileNames ;
00185
00186 int m_ImageWidth;
00187 int m_ImageHeight;
00188
00189 double m_k1, m_k2, m_p1, m_p2;
00190 };
00191
00194 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_VirtualCam();
00195
00196 }
00197 #endif // __IPA_VIRTUALRANGECAM_H__
00198
00199