18 #include "../include/cob_camera_sensors/StdAfx.h" 26 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/VisionUtils.h" 27 #include "cob_vision/windows/src/extern/TinyXml/tinyxml.h" 30 #include <opencv/highgui.h> 32 namespace fs = boost::filesystem;
74 std::cerr <<
"ERROR - VirtualRangeCam::Init:" << std::endl;
75 std::cerr <<
"\t ... Parsing xml configuration file failed" << std::endl;
83 std::string filename = directory +
"MatlabCalibrationData/PMD/ZCoeffsA0.xml";
84 CvMat* c_mat = (CvMat*)cvLoad(filename.c_str());
87 std::cerr <<
"ERROR - PMDCamCube::LoadParameters:" << std::endl;
88 std::cerr <<
"\t ... Error while loading " << directory +
"MatlabCalibrationData/ZcoeffsA0.txt" <<
"." << std::endl;
89 std::cerr <<
"\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
99 filename = directory +
"MatlabCalibrationData/PMD/ZCoeffsA1.xml";
100 c_mat = (CvMat*)cvLoad(filename.c_str());
103 std::cerr <<
"ERROR - PMDCamCube::LoadParameters:" << std::endl;
104 std::cerr <<
"\t ... Error while loading " << directory +
"MatlabCalibrationData/ZcoeffsA1.txt" <<
"." << std::endl;
105 std::cerr <<
"\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
112 cvReleaseMat(&c_mat);
115 filename = directory +
"MatlabCalibrationData/PMD/ZCoeffsA2.xml";
116 c_mat = (CvMat*)cvLoad(filename.c_str());
119 std::cerr <<
"ERROR - PMDCamCube::LoadParameters:" << std::endl;
120 std::cerr <<
"\t ... Error while loading " << directory +
"MatlabCalibrationData/ZcoeffsA2.txt" <<
"." << std::endl;
121 std::cerr <<
"\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
128 cvReleaseMat(&c_mat);
131 filename = directory +
"MatlabCalibrationData/PMD/ZCoeffsA3.xml";
132 c_mat = (CvMat*)cvLoad(filename.c_str());
135 std::cerr <<
"ERROR - PMDCamCube::LoadParameters:" << std::endl;
136 std::cerr <<
"\t ... Error while loading " << directory +
"MatlabCalibrationData/ZcoeffsA3.txt" <<
"." << std::endl;
137 std::cerr <<
"\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
144 cvReleaseMat(&c_mat);
147 filename = directory +
"MatlabCalibrationData/PMD/ZCoeffsA4.xml";
148 c_mat = (CvMat*)cvLoad(filename.c_str());
151 std::cerr <<
"ERROR - PMDCamCube::LoadParameters:" << std::endl;
152 std::cerr <<
"\t ... Error while loading " << directory +
"MatlabCalibrationData/ZcoeffsA4.txt" <<
"." << std::endl;
153 std::cerr <<
"\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
160 cvReleaseMat(&c_mat);
163 filename = directory +
"MatlabCalibrationData/PMD/ZCoeffsA5.xml";
164 c_mat = (CvMat*)cvLoad(filename.c_str());
167 std::cerr <<
"ERROR - PMDCamCube::LoadParameters:" << std::endl;
168 std::cerr <<
"\t ... Error while loading " << directory +
"MatlabCalibrationData/ZcoeffsA5.txt" <<
"." << std::endl;
169 std::cerr <<
"\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
176 cvReleaseMat(&c_mat);
179 filename = directory +
"MatlabCalibrationData/PMD/ZCoeffsA6.xml";
180 c_mat = (CvMat*)cvLoad(filename.c_str());
183 std::cerr <<
"ERROR - PMDCamCube::LoadParameters:" << std::endl;
184 std::cerr <<
"\t ... Error while loading " << directory +
"MatlabCalibrationData/ZcoeffsA6.txt" <<
"." << std::endl;
185 std::cerr <<
"\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
192 cvReleaseMat(&c_mat);
211 IplImage* image = (IplImage*) cvLoad(filename.c_str(), 0);
214 cvReleaseImage(&image);
229 if (itCounter->second > 0)
231 if (ext ==
"") ext = itCounter->first;
234 std::cerr <<
"ERROR - VirtualRangeCam::Open:\n";
235 std::cerr <<
"\t ... The provided path contains data in mixed formats (e.g. .xml and .bin).\n";
255 std::stringstream ss;
256 std::string sCameraIndex;
265 if ( !fs::exists( absoluteDirectoryName ) )
267 std::cerr <<
"ERROR - VirtualRangeCam::Open:" << std::endl;
268 std::cerr <<
"\t ... Path '" << absoluteDirectoryName.file_string() <<
"' not found" << std::endl;
272 std::vector<std::string> extensionList;
273 extensionList.push_back(
".xml"); extensionList.push_back(
".bin"); extensionList.push_back(
".png"); extensionList.push_back(
".jpg"); extensionList.push_back(
".bmp");
274 std::map<std::string, int> amplitudeImageCounter;
275 std::map<std::string, int> intensityImageCounter;
276 std::map<std::string, int> coordinateImageCounter;
277 std::map<std::string, int> rangeImageCounter;
278 std::map<std::string, std::vector<std::string> > amplitudeImageFileNames;
279 std::map<std::string, std::vector<std::string> > intensityImageFileNames;
280 std::map<std::string, std::vector<std::string> > coordinateImageFileNames;
281 std::map<std::string, std::vector<std::string> > rangeImageFileNames;
283 if ( fs::exists( absoluteDirectoryName ) )
285 std::cout <<
"INFO - VirtualRangeCam::Open :" << std::endl;
286 std::cout <<
"\t ... Parsing directory '" << absoluteDirectoryName.directory_string() <<
"'" << std::endl;
288 fs::directory_iterator end_iter;
289 for ( fs::directory_iterator dir_itr( absoluteDirectoryName ); dir_itr != end_iter; ++dir_itr )
293 if (fs::is_regular_file(dir_itr->status()))
295 std::string filename = dir_itr->path().string();
298 for (
unsigned int extIndex=0; extIndex<extensionList.size(); extIndex++)
300 std::string ext = extensionList[extIndex];
301 std::string format =
"32F1_";
302 if (extIndex>=2) format =
"8U3_";
303 if ((dir_itr->path().extension() == ext) && filename.find(
"RangeCamIntensity_" + format + sCameraIndex, 0 ) != std::string::npos)
305 (intensityImageCounter.find(ext) == intensityImageCounter.end()) ? intensityImageCounter[ext] = 1 : intensityImageCounter[ext]++;
307 intensityImageFileNames[ext].push_back(filename);
313 for (
unsigned int extIndex=0; extIndex<2; extIndex++)
315 std::string ext = extensionList[extIndex];
316 if ((dir_itr->path().extension() == ext) && filename.find(
"RangeCamAmplitude_32F1_" + sCameraIndex, 0 ) != std::string::npos)
318 (amplitudeImageCounter.find(ext) == amplitudeImageCounter.end()) ? amplitudeImageCounter[ext] = 1 : amplitudeImageCounter[ext]++;
320 amplitudeImageFileNames[ext].push_back(filename);
326 for (
unsigned int extIndex=0; extIndex<2; extIndex++)
328 std::string ext = extensionList[extIndex];
329 if ((dir_itr->path().extension() == ext) && filename.find(
"RangeCamCoordinate_32F3_" + sCameraIndex, 0 ) != std::string::npos)
331 (coordinateImageCounter.find(ext) == coordinateImageCounter.end()) ? coordinateImageCounter[ext] = 1 : coordinateImageCounter[ext]++;
332 coordinateImageFileNames[ext].push_back(filename);
339 for (
unsigned int extIndex=0; extIndex<2; extIndex++)
341 std::string ext = extensionList[extIndex];
342 if ((dir_itr->path().extension() == ext) && filename.find(
"RangeCamRange_32F1_" + sCameraIndex, 0 ) != std::string::npos)
344 (rangeImageCounter.find(ext) == rangeImageCounter.end()) ? rangeImageCounter[ext] = 1 : rangeImageCounter[ext]++;
346 rangeImageFileNames[ext].push_back(filename);
352 catch (
const std::exception &ex )
354 std::cout <<
"WARNING - VirtualRangeCam::Open:" << std::endl;
355 std::cout <<
"\t ... Exception catch of '" << ex.what() <<
"'" << std::endl;
359 std::map<std::string, int>::iterator itCounter;
360 std::string extInt =
"";
361 for (itCounter = intensityImageCounter.begin(); itCounter != intensityImageCounter.end(); itCounter++)
FindSourceImageFormat(itCounter, extInt);
365 std::string extAmp =
"";
366 for (itCounter = amplitudeImageCounter.begin(); itCounter != amplitudeImageCounter.end(); itCounter++)
FindSourceImageFormat(itCounter, extAmp);
370 std::string extCoord =
"";
371 for (itCounter = coordinateImageCounter.begin(); itCounter != coordinateImageCounter.end(); itCounter++)
FindSourceImageFormat(itCounter, extCoord);
375 std::string extRange =
"";
376 for (itCounter = rangeImageCounter.begin(); itCounter != rangeImageCounter.end(); itCounter++)
FindSourceImageFormat(itCounter, extRange);
383 std::cout <<
"INFO - VirtualRangeCam::Open:" << std::endl;
384 std::cout <<
"\t ... Extracted '" << intensityImageCounter[extInt] <<
"' intensity images (3*8 or 16 bit/value)\n";
385 std::cout <<
"\t ... Extracted '" << amplitudeImageCounter[extAmp] <<
"' amplitude images (16 bit/value)\n";
386 std::cout <<
"\t ... Extracted '" << coordinateImageCounter[extCoord] <<
"' coordinate images (3*16 bit/value)\n";
387 std::cout <<
"\t ... Extracted '" << rangeImageCounter[extRange] <<
"' range images (16 bit/value)\n";
389 if (intensityImageCounter[extInt] == 0 && amplitudeImageCounter[extAmp] == 0)
391 std::cerr <<
"ERROR - VirtualRangeCam::Open:" << std::endl;
392 std::cerr <<
"\t ... Could not detect any intensity or amplitude images" << std::endl;
393 std::cerr <<
"\t ... from the specified directory." << std::endl;
397 if (coordinateImageCounter[extCoord] != 0 &&
398 ((intensityImageCounter[extInt] != coordinateImageCounter[extCoord] &&
399 amplitudeImageCounter[extAmp] != coordinateImageCounter[extCoord]) ||
400 (coordinateImageCounter[extCoord] != rangeImageCounter[extRange])))
402 std::cerr <<
"ERROR - VirtualRangeCam::Open:" << std::endl;
403 std::cerr <<
"\t ... Number of intensity, range and coordinate images must agree." << std::endl;
409 std::cerr <<
"ERROR - VirtualRangeCam::Open:" << std::endl;
410 std::cerr <<
"\t ... Coordinate images must be available for calibration mode NATIVE or MATLAB_NO_Z." << std::endl;
416 std::cerr <<
"ERROR - VirtualRangeCam::Open():" << std::endl;
417 std::cerr <<
"\t ... Path '" << absoluteDirectoryName.file_string() <<
"' is not a directory." << std::endl;
422 std::cout <<
"**************************************************" << std::endl;
423 std::cout <<
"VirtualRangeCam::Open(): Virtual range camera OPEN" << std::endl;
424 std::cout <<
"**************************************************" << std::endl<< std::endl;
451 std::cerr <<
"ERROR - VirtualRangeCam::SetProperty:" << std::endl;
452 std::cerr <<
"\t ... Property " << cameraProperty->
propertyID <<
" unspecified.\n";
483 std::cerr <<
"VirtualRangeCam::GetProperty:" << std::endl;
484 std::cerr <<
"\t ... Property " << cameraProperty->
propertyID <<
" unspecified.";
501 char* rangeImageData = 0;
502 char* grayImageData = 0;
503 char* cartesianImageData = 0;
504 int widthStepRange = -1;
505 int widthStepGray = -1;
506 int widthStepCartesian = -1;
511 rangeImageData = (
char*) rangeImage->data;
512 widthStepRange = rangeImage->step;
519 grayImageData = (
char*) grayImage->data;
520 widthStepGray = grayImage->step;
526 cartesianImageData = (
char*) cartesianImage->data;
527 widthStepCartesian = cartesianImage->step;
530 if (widthStepRange+widthStepGray+widthStepCartesian == -3)
535 return AcquireImages(widthStepRange, widthStepGray, widthStepCartesian, rangeImageData, grayImageData, cartesianImageData, getLatestFrame, undistort, grayImageType);
539 unsigned long VirtualRangeCam::AcquireImages(
int widthStepRange,
int widthStepGray,
int widthStepCartesian,
char* rangeImageData,
char* grayImageData,
char* cartesianImageData,
544 std::cerr <<
"ERROR - VirtualRangeCam::AcquireImages:" << std::endl;
545 std::cerr <<
"\t ... Camera not open." << std::endl;
555 float* f_ptr_dst = 0;
556 bool releaseNecessary =
false;
560 IplImage* rangeImage = &rangeIpl;
564 rangeIpl = (IplImage)rangeMat;
569 releaseNecessary =
true;
573 std::cerr <<
"ERROR - VirtualRangeCam::AcquireImages:\n";
581 for(
unsigned int row=0; row<(
unsigned int)
m_ImageHeight; row++)
583 f_ptr = (
float*) (rangeImage->imageData + row*rangeImage->widthStep);
584 f_ptr_dst = (
float*) (rangeImageData + row*widthStepRange);
586 for (
unsigned int col=0; col<(
unsigned int)
m_ImageWidth; col++)
588 f_ptr_dst[col] = f_ptr[col];
595 cv::Mat cpp_rangeImage = rangeImage;
601 if (releaseNecessary) cvReleaseImage(&rangeImage);
609 float* f_ptr_dst = 0;
610 unsigned char* uc_ptr = 0;
611 unsigned char* uc_ptr_dst = 0;
614 IplImage* grayImage = &grayIpl;
615 bool releaseNecessary =
false;
618 if ((grayImageType == ipa_CameraSensors::INTENSITY_32F1) || (grayImageType == ipa_CameraSensors::INTENSITY_8U3))
624 grayIpl = (IplImage)grayMat;
629 releaseNecessary =
true;
635 grayIpl = (IplImage)grayMat;
639 std::cerr <<
"ERROR - VirtualRangeCam::AcquireImages:\n";
650 grayIpl = (IplImage)grayMat;
655 releaseNecessary =
true;
659 std::cerr <<
"ERROR - VirtualRangeCam::AcquireImages:\n";
668 if (grayImageType == ipa_CameraSensors::INTENSITY_8U3)
670 for(
unsigned int row=0; row<(
unsigned int)
m_ImageHeight; row++)
672 f_ptr = (
float*) (grayImage->imageData + row*grayImage->widthStep);
673 f_ptr_dst = (
float*) (grayImageData + row*widthStepGray);
675 for (
unsigned int col=0; col<(
unsigned int)
m_ImageWidth; col++)
677 f_ptr_dst[col] = f_ptr[col];
683 for(
unsigned int row=0; row<(
unsigned int)
m_ImageHeight; row++)
685 uc_ptr = (
unsigned char*) (grayImage->imageData + row*grayImage->widthStep);
686 uc_ptr_dst = (
unsigned char*) (grayImageData + row*widthStepGray);
688 for (
unsigned int col=0; col<(
unsigned int)
m_ImageWidth; col++)
690 uc_ptr_dst[col] = uc_ptr[col];
697 cv::Mat undistortedData;
698 if (grayImageType == ipa_CameraSensors::INTENSITY_8U3)
706 cv::Mat cpp_grayImage = grayImage;
712 if (releaseNecessary) cvReleaseImage(&grayImage);
717 if(cartesianImageData)
721 float zCalibrated = -1;
723 float* f_ptr_dst = 0;
724 bool releaseNecessary =
false;
735 cv::Mat coordinateMat;
736 IplImage coordinateIpl;
737 IplImage* coordinateImage = &coordinateIpl;
741 coordinateIpl = (IplImage)coordinateMat;
746 releaseNecessary =
true;
750 std::cerr <<
"ERROR - VirtualRangeCam::AcquireImages:\n";
755 for(
unsigned int row=0; row<(
unsigned int)
m_ImageHeight; row++)
757 f_ptr = (
float*) (coordinateImage->imageData + row*coordinateImage->widthStep);
758 f_ptr_dst = (
float*) (cartesianImageData + row*widthStepCartesian);
760 for (
unsigned int col=0; col<(
unsigned int)
m_ImageWidth; col++)
762 int colTimes3 = 3*col;
764 zCalibrated = f_ptr[colTimes3+2];
767 f_ptr_dst[colTimes3] = x;
768 f_ptr_dst[colTimes3 + 1] = y;
769 f_ptr_dst[colTimes3 + 2] = zCalibrated;
771 if (f_ptr_dst[colTimes3 + 2] < 0)
773 std::cout <<
"<0: " << row <<
" " << col <<
"\n";
777 if (releaseNecessary) cvReleaseImage(&coordinateImage);
781 cv::Mat coordinateMat;
782 IplImage coordinateIpl;
783 IplImage* coordinateImage = &coordinateIpl;
787 coordinateIpl = (IplImage)coordinateMat;
792 releaseNecessary =
true;
796 std::cerr <<
"ERROR - VirtualRangeCam::AcquireImages:\n";
801 for(
unsigned int row=0; row<(
unsigned int)
m_ImageHeight; row++)
803 f_ptr = (
float*) (coordinateImage->imageData + row*coordinateImage->widthStep);
804 f_ptr_dst = (
float*) (cartesianImageData + row*widthStepCartesian);
806 for (
unsigned int col=0; col<(
unsigned int)
m_ImageWidth; col++)
808 int colTimes3 = 3*col;
810 f_ptr_dst[colTimes3] =f_ptr[colTimes3+0];;
811 f_ptr_dst[colTimes3 + 1] = f_ptr[colTimes3+1];
812 f_ptr_dst[colTimes3 + 2] = f_ptr[colTimes3+2];
815 if (releaseNecessary) cvReleaseImage(&coordinateImage);
819 std::cerr <<
"ERROR - VirtualRangeCam::AcquireImages:" << std::endl;
820 std::cerr <<
"\t ... Calibration method unknown.\n";
849 int min=std::numeric_limits<int>::max();
881 zCalibrated = (float) y;
891 double fx, fy, cx, cy;
902 std::cerr <<
"VirtualRangeCam::GetCalibratedXYMatlab:" << std::endl;
903 std::cerr <<
"\t ... fx is 0.\n";
906 x = (float) (z*(u-cx)/fx) ;
911 std::cerr <<
"VirtualRangeCam::GetCalibratedXYMatlab:" << std::endl;
912 std::cerr <<
"\t ... fy is 0.\n";
915 y = (float) (z*(v-cy)/fy);
928 double fx, fy, cx, cy;
943 std::cerr <<
"ERROR - VirtualRangeCam::GetCalibratedUV:" << std::endl;
944 std::cerr <<
"\t ... z is 0.\n";
954 std::cerr <<
"ERROR - VirtualRangeCam::GetCalibratedUV:" << std::endl;
955 std::cerr <<
"\t ... Function not implemented.\n";
974 if (!p_configXmlDocument->LoadFile())
976 std::cerr <<
"ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
977 std::cerr <<
"\t ... Error while loading xml configuration file" << std::endl;
978 std::cerr <<
"\t ...(Check filename and syntax):" << std::endl;
979 std::cerr <<
"\t ... " << filename << std::endl;
982 std::cout <<
"INFO - VirtualRangeCam::LoadParameters:" << std::endl;
983 std::cout <<
"\t ... Parsing xml configuration file" << std::endl;
984 std::cout <<
"\t ... '" << filename <<
"'" << std::endl;
986 if ( p_configXmlDocument )
993 TiXmlElement *p_xmlElement_Root = NULL;
994 p_xmlElement_Root = p_configXmlDocument->FirstChildElement(
"LibCameraSensors" );
996 if ( p_xmlElement_Root )
1003 TiXmlElement *p_xmlElement_Root_VirtualRangeCam = NULL;
1004 std::stringstream ss;
1005 ss <<
"VirtualRangeCam_" << cameraIndex;
1006 p_xmlElement_Root_VirtualRangeCam = p_xmlElement_Root->FirstChildElement( ss.str() );
1007 if ( p_xmlElement_Root_VirtualRangeCam )
1014 TiXmlElement *p_xmlElement_Child = NULL;
1015 p_xmlElement_Child = p_xmlElement_Root_VirtualRangeCam->FirstChildElement(
"CameraDataDirectory" );
1016 if ( p_xmlElement_Child )
1019 std::string tempString;
1020 if ( p_xmlElement_Child->QueryValueAttribute(
"relativePath", &tempString ) != TIXML_SUCCESS)
1022 std::cerr <<
"ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
1023 std::cerr <<
"\t ... Can't find attribute 'relativePath' of tag 'CameraDataDirectory'." << std::endl;
1031 std::cerr <<
"ERROR - VirtualColorCam::LoadParameters:" << std::endl;
1032 std::cerr <<
"\t ... Can't find tag 'CameraDataDirectory'." << std::endl;
1040 p_xmlElement_Child = NULL;
1041 p_xmlElement_Child = p_xmlElement_Root_VirtualRangeCam->FirstChildElement(
"CalibrationMethod" );
1042 std::string tempString;
1043 if ( p_xmlElement_Child )
1046 if ( p_xmlElement_Child->QueryValueAttribute(
"name", &tempString ) != TIXML_SUCCESS)
1048 std::cerr <<
"ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
1049 std::cerr <<
"\t ... Can't find attribute 'name' of tag 'CalibrationMethod'." << std::endl;
1057 std::cerr <<
"ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
1058 std::cerr <<
"\t ... Calibration mode " << tempString <<
" unspecified." << std::endl;
1064 std::cerr <<
"ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
1065 std::cerr <<
"\t ... Can't find tag 'CalibrationMethod'." << std::endl;
1074 std::cerr <<
"ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
1075 std::cerr <<
"\t ... Can't find tag '" << ss.str() <<
"'" << std::endl;
1085 std::cerr <<
"ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
1086 std::cerr <<
"\t ... Can't find tag 'LibCameraSensors'." << std::endl;
1091 std::cout <<
"\t ... Parsing xml calibration file ... [OK] \n";
std::vector< std::string > m_AmplitudeImageFileNames
int m_ImageWidth
Image width.
cv::Mat m_intrinsicMatrix
Intrinsic parameters [fx 0 cx; 0 fy cy; 0 0 1].
cv::Mat m_CoeffsA4
a4 z-calibration parameters. One matrix entry corresponds to one pixel
t_CalibrationMethod m_CalibrationMethod
Calibration method MATLAB, MATLAB_NO_Z or SWISSRANGER.
unsigned long GetCalibratedXYMatlab(int u, int v, float z, float &x, float &y)
unsigned long SetPathToImages(std::string path)
unsigned long LoadParameters(const char *filename, int cameraIndex)
t_cameraResolution cameraResolution
RET_FUNCTION_NOT_IMPLEMENTED
cv::Mat m_CoeffsA3
a3 z-calibration parameters. One matrix entry corresponds to one pixel
unsigned long SaveParameters(const char *filename)
__DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_VirtualCam()
unsigned long LoadMat(cv::Mat &mat, std::string filename, int type=CV_32F)
void FindSourceImageFormat(std::map< std::string, int >::iterator &itCounter, std::string &ext)
unsigned long Init(std::string directory, int cameraIndex=0)
RET_CAMERA_NOT_INITIALIZED
unsigned long GetCalibratedZMatlab(int u, int v, float zRaw, float &zCalibrated)
unsigned long AcquireImages(int widthStepRange, int widthStepGray, int widthStepCartesian, char *rangeImage=NULL, char *intensityImage=NULL, char *cartesianImage=NULL, bool getLatestFrame=true, bool undistort=true, ipa_CameraSensors::t_ToFGrayImageType grayImageType=ipa_CameraSensors::INTENSITY_32F1)
t_cameraType m_CameraType
Camera Type.
unsigned int m_BufferSize
Number of images, the camera buffers internally.
std::vector< std::string > m_IntensityImageFileNames
RET_CAMERA_ALREADY_INITIALIZED
boost::shared_ptr< AbstractRangeImagingSensor > AbstractRangeImagingSensorPtr
cv::Mat m_undistortMapX
The output array of x coordinates for the undistortion map.
cv::Mat m_CoeffsA0
a0 z-calibration parameters. One matrix entry corresponds to one pixel
cv::Mat m_CoeffsA6
a6 z-calibration parameters. One matrix entry corresponds to one pixel
int m_ImageHeight
Image height.
unsigned long GetCalibratedUV(double x, double y, double z, double &u, double &v)
cv::Mat m_CoeffsA2
a2 z-calibration parameters. One matrix entry corresponds to one pixel
cv::Mat m_CoeffsA1
a1 z-calibration parameters. One matrix entry corresponds to one pixel
unsigned int u_integerData
unsigned int m_ImageCounter
Holds the index of the image that is extracted during the next call of AcquireImages ...
t_cameraPropertyID propertyID
cv::Mat m_CoeffsA5
a5 z-calibration parameters. One matrix entry corresponds to one pixel
unsigned long EvaluatePolynomial(double x, int degree, double *coefficients, double *y)
unsigned long SetPropertyDefaults()
cv::Mat m_undistortMapY
The output array of Y coordinates for the undistortion map.
int m_CameraIndex
Index of the specified camera. Important, when several cameras of the same type are present...
bool m_initialized
True, when the camera has sucessfully been initialized.
void UpdateImageDimensionsOnFirstImage(std::string filename, std::string ext=".xml")
std::vector< std::string > m_CoordinateImageFileNames
unsigned long propertyType
unsigned long GetProperty(t_cameraProperty *cameraProperty)
std::vector< std::string > m_RangeImageFileNames
unsigned long SetProperty(t_cameraProperty *cameraProperty)
std::string m_CameraDataDirectory
Directory where the image data resides.
#define __DLL_LIBCAMERASENSORS__
bool m_open
True, when the camera has sucessfully been opend.