VirtualRangeCam.cpp
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 
00018 #include "../include/cob_camera_sensors/StdAfx.h"
00019 
00020 #ifdef __LINUX__
00021 #include "cob_camera_sensors/VirtualRangeCam.h"
00022 #include "cob_vision_utils/VisionUtils.h"
00023 #include "tinyxml.h"
00024 #else
00025 #include "cob_driver/cob_camera_sensors/common/include/cob_camera_sensors/VirtualRangeCam.h"
00026 #include "cob_common/cob_vision_utils/common/include/cob_vision_utils/VisionUtils.h"
00027 #include "cob_vision/windows/src/extern/TinyXml/tinyxml.h"
00028 #endif
00029 
00030 #include <opencv/highgui.h>
00031 
00032 namespace fs = boost::filesystem;
00033 using namespace ipa_CameraSensors;
00034 
00035 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr ipa_CameraSensors::CreateRangeImagingSensor_VirtualCam()
00036 {
00037         return AbstractRangeImagingSensorPtr(new VirtualRangeCam());
00038 }
00039 
00040 VirtualRangeCam::VirtualRangeCam()
00041 {
00042         m_initialized = false;
00043         m_open = false;
00044 
00045         m_BufferSize = 1;
00046 
00047         m_ImageCounter = 0;
00048 }
00049 
00050 
00051 VirtualRangeCam::~VirtualRangeCam()
00052 {
00053         if (isOpen())
00054         {
00055                 Close();
00056         }
00057 }
00058 
00059 unsigned long VirtualRangeCam::Init(std::string directory, int cameraIndex)
00060 {
00061         if (isInitialized())
00062         {
00063                 return (RET_OK | RET_CAMERA_ALREADY_INITIALIZED);
00064         }
00065 
00066         m_CameraType = ipa_CameraSensors::CAM_VIRTUALRANGE;
00067 
00068         // It is important to put this before LoadParameters
00069         m_CameraDataDirectory = directory;
00070 
00071         // Load SR parameters from xml-file
00072         if (LoadParameters((directory + "cameraSensorsIni.xml").c_str(), cameraIndex) & RET_FAILED)
00073         {
00074                 std::cerr << "ERROR - VirtualRangeCam::Init:" << std::endl;
00075                 std::cerr << "\t ... Parsing xml configuration file failed" << std::endl;
00076                 return (RET_FAILED | RET_INIT_CAMERA_FAILED);
00077         }
00078 
00079         m_CoeffsInitialized = true;
00080         if (m_CalibrationMethod == MATLAB)
00081         {
00082                 // Load z-calibration files
00083                 std::string filename = directory + "MatlabCalibrationData/PMD/ZCoeffsA0.xml";
00084                 CvMat* c_mat = (CvMat*)cvLoad(filename.c_str());
00085                 if (! c_mat)
00086                 {
00087                         std::cerr << "ERROR - PMDCamCube::LoadParameters:" << std::endl;
00088                         std::cerr << "\t ... Error while loading " << directory + "MatlabCalibrationData/ZcoeffsA0.txt" << "." << std::endl;
00089                         std::cerr << "\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
00090                         m_CoeffsInitialized = false;
00091                         // no RET_FAILED, as we might want to calibrate the camera to create these files
00092                 }
00093                 else
00094                 {
00095                         m_CoeffsA0 = c_mat;
00096                         cvReleaseMat(&c_mat);
00097                 }
00098 
00099                 filename = directory + "MatlabCalibrationData/PMD/ZCoeffsA1.xml";
00100                 c_mat = (CvMat*)cvLoad(filename.c_str());
00101                 if (! c_mat)
00102                 {
00103                         std::cerr << "ERROR - PMDCamCube::LoadParameters:" << std::endl;
00104                         std::cerr << "\t ... Error while loading " << directory + "MatlabCalibrationData/ZcoeffsA1.txt" << "." << std::endl;
00105                         std::cerr << "\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
00106                         m_CoeffsInitialized = false;
00107                         // no RET_FAILED, as we might want to calibrate the camera to create these files
00108                 }
00109                 else
00110                 {
00111                         m_CoeffsA1 = c_mat;
00112                         cvReleaseMat(&c_mat);
00113                 }
00114 
00115                 filename = directory + "MatlabCalibrationData/PMD/ZCoeffsA2.xml";
00116                 c_mat = (CvMat*)cvLoad(filename.c_str());
00117                 if (! c_mat)
00118                 {
00119                         std::cerr << "ERROR - PMDCamCube::LoadParameters:" << std::endl;
00120                         std::cerr << "\t ... Error while loading " << directory + "MatlabCalibrationData/ZcoeffsA2.txt" << "." << std::endl;
00121                         std::cerr << "\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
00122                         m_CoeffsInitialized = false;
00123                         // no RET_FAILED, as we might want to calibrate the camera to create these files
00124                 }
00125                 else
00126                 {
00127                         m_CoeffsA2 = c_mat;
00128                         cvReleaseMat(&c_mat);
00129                 }
00130 
00131                 filename = directory + "MatlabCalibrationData/PMD/ZCoeffsA3.xml";
00132                 c_mat = (CvMat*)cvLoad(filename.c_str());
00133                 if (! c_mat)
00134                 {
00135                         std::cerr << "ERROR - PMDCamCube::LoadParameters:" << std::endl;
00136                         std::cerr << "\t ... Error while loading " << directory + "MatlabCalibrationData/ZcoeffsA3.txt" << "." << std::endl;
00137                         std::cerr << "\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
00138                         m_CoeffsInitialized = false;
00139                         // no RET_FAILED, as we might want to calibrate the camera to create these files
00140                 }
00141                 else
00142                 {
00143                         m_CoeffsA3 = c_mat;
00144                         cvReleaseMat(&c_mat);
00145                 }
00146 
00147                 filename = directory + "MatlabCalibrationData/PMD/ZCoeffsA4.xml";
00148                 c_mat = (CvMat*)cvLoad(filename.c_str());
00149                 if (! c_mat)
00150                 {
00151                         std::cerr << "ERROR - PMDCamCube::LoadParameters:" << std::endl;
00152                         std::cerr << "\t ... Error while loading " << directory + "MatlabCalibrationData/ZcoeffsA4.txt" << "." << std::endl;
00153                         std::cerr << "\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
00154                         m_CoeffsInitialized = false;
00155                         // no RET_FAILED, as we might want to calibrate the camera to create these files
00156                 }
00157                 else
00158                 {
00159                         m_CoeffsA4 = c_mat;
00160                         cvReleaseMat(&c_mat);
00161                 }
00162 
00163                 filename = directory + "MatlabCalibrationData/PMD/ZCoeffsA5.xml";
00164                 c_mat = (CvMat*)cvLoad(filename.c_str());
00165                 if (! c_mat)
00166                 {
00167                         std::cerr << "ERROR - PMDCamCube::LoadParameters:" << std::endl;
00168                         std::cerr << "\t ... Error while loading " << directory + "MatlabCalibrationData/ZcoeffsA5.txt" << "." << std::endl;
00169                         std::cerr << "\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
00170                         m_CoeffsInitialized = false;
00171                         // no RET_FAILED, as we might want to calibrate the camera to create these files
00172                 }
00173                 else
00174                 {
00175                         m_CoeffsA5 = c_mat;
00176                         cvReleaseMat(&c_mat);
00177                 }
00178 
00179                 filename = directory + "MatlabCalibrationData/PMD/ZCoeffsA6.xml";
00180                 c_mat = (CvMat*)cvLoad(filename.c_str());
00181                 if (! c_mat)
00182                 {
00183                         std::cerr << "ERROR - PMDCamCube::LoadParameters:" << std::endl;
00184                         std::cerr << "\t ... Error while loading " << directory + "MatlabCalibrationData/ZcoeffsA6.txt" << "." << std::endl;
00185                         std::cerr << "\t ... Data is necessary for z-calibration of swissranger camera" << std::endl;
00186                         m_CoeffsInitialized = false;
00187                         // no RET_FAILED, as we might want to calibrate the camera to create these files
00188                 }
00189                 else
00190                 {
00191                         m_CoeffsA6 = c_mat;
00192                         cvReleaseMat(&c_mat);
00193                 }
00194         }
00195 
00196         m_CameraIndex = cameraIndex;
00197 
00198         // set init flag
00199         m_initialized = true;
00200 
00201         return RET_OK;
00202 }
00203 
00204 
00205 inline void VirtualRangeCam::UpdateImageDimensionsOnFirstImage(std::string filename, std::string ext)
00206 {
00207         if (m_ImageWidth == -1 || m_ImageHeight == -1)
00208         {
00209                 if (ext != ".bin")
00210                 {
00211                         IplImage* image = (IplImage*) cvLoad(filename.c_str(), 0);
00212                         m_ImageWidth = image->width;
00213                         m_ImageHeight = image->height;
00214                         cvReleaseImage(&image);
00215                 }
00216                 else
00217                 {
00218                         cv::Mat mat;
00219                         ipa_Utils::LoadMat(mat, filename);
00220                         m_ImageHeight = mat.rows;
00221                         m_ImageWidth = mat.cols;
00222                 }
00223         }
00224 }
00225 
00226 
00227 inline void VirtualRangeCam::FindSourceImageFormat(std::map<std::string, int>::iterator& itCounter, std::string& ext)
00228 {
00229         if (itCounter->second > 0)
00230         {
00231                 if (ext == "") ext = itCounter->first;
00232                 else
00233                 {
00234                         std::cerr << "ERROR - VirtualRangeCam::Open:\n";
00235                         std::cerr << "\t ... The provided path contains data in mixed formats (e.g. .xml and .bin).\n";
00236                         assert(false);
00237                 }
00238         }
00239 }
00240 
00241 
00242 unsigned long VirtualRangeCam::Open()
00243 {
00244         if (!isInitialized())
00245         {
00246                 return (RET_FAILED | RET_CAMERA_NOT_INITIALIZED);
00247         }
00248 
00249         if (isOpen())
00250         {
00251                 return (RET_OK | RET_CAMERA_ALREADY_OPEN);
00252         }
00253 
00254         // Convert camera ID to string
00255         std::stringstream ss;
00256         std::string sCameraIndex;
00257         ss << m_CameraIndex;
00258         ss >> sCameraIndex;
00259 
00260         m_ImageWidth = -1;
00261         m_ImageHeight = -1;
00262 
00263         // Create absolute filename and check if directory exists
00264         fs::path absoluteDirectoryName( m_CameraDataDirectory );
00265         if ( !fs::exists( absoluteDirectoryName ) )
00266         {
00267                 std::cerr << "ERROR - VirtualRangeCam::Open:" << std::endl;
00268                 std::cerr << "\t ... Path '" << absoluteDirectoryName.file_string() << "' not found" << std::endl;
00269                 return (ipa_CameraSensors::RET_FAILED | ipa_CameraSensors::RET_FAILED_OPEN_FILE);
00270         }
00271 
00272         std::vector<std::string> extensionList;
00273         extensionList.push_back(".xml"); extensionList.push_back(".bin"); extensionList.push_back(".png"); extensionList.push_back(".jpg"); extensionList.push_back(".bmp");
00274         std::map<std::string, int> amplitudeImageCounter;       // first index is the extension (.xml, .bin), second is the number of such images found
00275         std::map<std::string, int> intensityImageCounter;       // first index is the extension (.xml, .bin, .png, .jpg, .bmp), second is the number of such images found
00276         std::map<std::string, int> coordinateImageCounter;      // first index is the extension (.xml, .bin), second is the number of such images found
00277         std::map<std::string, int> rangeImageCounter;           // first index is the extension (.xml, .bin), second is the number of such images found
00278         std::map<std::string, std::vector<std::string> > amplitudeImageFileNames;       // first index is the extension (.xml, .bin), second is the vector of file names
00279         std::map<std::string, std::vector<std::string> > intensityImageFileNames;       // first index is the extension (.xml, .bin, .png, .jpg, .bmp), second is the vector of file names
00280         std::map<std::string, std::vector<std::string> > coordinateImageFileNames;      // first index is the extension (.xml, .bin), second is the vector of file names
00281         std::map<std::string, std::vector<std::string> > rangeImageFileNames;           // first index is the extension (.xml, .bin), second is the vector of file names
00282         // Extract all image filenames from the directory
00283         if ( fs::exists( absoluteDirectoryName ) )
00284         {
00285                 std::cout << "INFO - VirtualRangeCam::Open   :" << std::endl;
00286                 std::cout << "\t ... Parsing directory '" << absoluteDirectoryName.directory_string() << "'" << std::endl;
00287 
00288                 fs::directory_iterator end_iter;
00289                 for ( fs::directory_iterator dir_itr( absoluteDirectoryName ); dir_itr != end_iter; ++dir_itr )
00290                 {
00291                         try
00292                         {
00293                                 if (fs::is_regular_file(dir_itr->status()))
00294                                 {
00295                                         std::string filename = dir_itr->path().string();
00296 
00297                                         // intensity image formats
00298                                         for (unsigned int extIndex=0; extIndex<extensionList.size(); extIndex++)
00299                                         {
00300                                                 std::string ext = extensionList[extIndex];
00301                                                 std::string format = "32F1_";
00302                                                 if (extIndex>=2) format = "8U3_";
00303                                                 if ((dir_itr->path().extension() == ext) && filename.find( "RangeCamIntensity_" + format + sCameraIndex, 0 ) != std::string::npos)
00304                                                 {
00305                                                         (intensityImageCounter.find(ext) == intensityImageCounter.end()) ? intensityImageCounter[ext] = 1 : intensityImageCounter[ext]++;
00306                                                         //std::cout << "VirtualRangeCam::Open(): Reading '" << filename << "\n";
00307                                                         intensityImageFileNames[ext].push_back(filename);
00308                                                         UpdateImageDimensionsOnFirstImage(filename, ext);
00309                                                 }
00310                                         }
00311 
00312                                         // amplitude image formats
00313                                         for (unsigned int extIndex=0; extIndex<2; extIndex++)
00314                                         {
00315                                                 std::string ext = extensionList[extIndex];
00316                                                 if ((dir_itr->path().extension() == ext) && filename.find( "RangeCamAmplitude_32F1_" + sCameraIndex, 0 ) != std::string::npos)
00317                                                 {
00318                                                         (amplitudeImageCounter.find(ext) == amplitudeImageCounter.end()) ? amplitudeImageCounter[ext] = 1 : amplitudeImageCounter[ext]++;
00319                                                         //std::cout << "VirtualRangeCam::Open(): Reading '" << filename << "\n";
00320                                                         amplitudeImageFileNames[ext].push_back(filename);
00321                                                         UpdateImageDimensionsOnFirstImage(filename, ext);
00322                                                 }
00323                                         }
00324 
00325                                         // coordinate image formats
00326                                         for (unsigned int extIndex=0; extIndex<2; extIndex++)
00327                                         {
00328                                                 std::string ext = extensionList[extIndex];
00329                                                 if ((dir_itr->path().extension() == ext) && filename.find( "RangeCamCoordinate_32F3_" + sCameraIndex, 0 ) != std::string::npos)
00330                                                 {
00331                                                         (coordinateImageCounter.find(ext) == coordinateImageCounter.end()) ? coordinateImageCounter[ext] = 1 : coordinateImageCounter[ext]++;
00332                                                         coordinateImageFileNames[ext].push_back(filename);
00333                                                         UpdateImageDimensionsOnFirstImage(filename, ext);
00334                                                         //std::cout << "VirtualRangeCam::Open(): Reading '" << filename << "\n";
00335                                                 }
00336                                         }
00337 
00338                                         // range image formats
00339                                         for (unsigned int extIndex=0; extIndex<2; extIndex++)
00340                                         {
00341                                                 std::string ext = extensionList[extIndex];
00342                                                 if ((dir_itr->path().extension() == ext) && filename.find( "RangeCamRange_32F1_" + sCameraIndex, 0 ) != std::string::npos)
00343                                                 {
00344                                                         (rangeImageCounter.find(ext) == rangeImageCounter.end()) ? rangeImageCounter[ext] = 1 : rangeImageCounter[ext]++;
00345                                                         //std::cout << "VirtualRangeCam::Open(): Reading '" << filename << "\n";
00346                                                         rangeImageFileNames[ext].push_back(filename);
00347                                                         UpdateImageDimensionsOnFirstImage(filename, ext);
00348                                                 }
00349                                         }
00350                                 }
00351                         }
00352                         catch ( const std::exception &ex )
00353                         {
00354                                 std::cout << "WARNING - VirtualRangeCam::Open:" << std::endl;
00355                                 std::cout << "\t ... Exception catch of '" << ex.what() << "'" << std::endl;
00356                         }
00357                 }
00358                 // intensity
00359                 std::map<std::string, int>::iterator itCounter;
00360                 std::string extInt = "";
00361                 for (itCounter = intensityImageCounter.begin(); itCounter != intensityImageCounter.end(); itCounter++) FindSourceImageFormat(itCounter, extInt);
00362                 if (extInt != "") m_IntensityImageFileNames = intensityImageFileNames[extInt];
00363 
00364                 // amplitude
00365                 std::string extAmp = "";
00366                 for (itCounter = amplitudeImageCounter.begin(); itCounter != amplitudeImageCounter.end(); itCounter++) FindSourceImageFormat(itCounter, extAmp);
00367                 if (extAmp != "") m_AmplitudeImageFileNames = amplitudeImageFileNames[extAmp];
00368 
00369                 // coordinates
00370                 std::string extCoord = "";
00371                 for (itCounter = coordinateImageCounter.begin(); itCounter != coordinateImageCounter.end(); itCounter++) FindSourceImageFormat(itCounter, extCoord);
00372                 if (extCoord != "") m_CoordinateImageFileNames = coordinateImageFileNames[extCoord];
00373 
00374                 // range
00375                 std::string extRange = "";
00376                 for (itCounter = rangeImageCounter.begin(); itCounter != rangeImageCounter.end(); itCounter++) FindSourceImageFormat(itCounter, extRange);
00377                 if (extRange != "") m_RangeImageFileNames = rangeImageFileNames[extRange];
00378 
00379                 std::sort(m_IntensityImageFileNames.begin(),m_IntensityImageFileNames.end());
00380                 std::sort(m_AmplitudeImageFileNames.begin(),m_AmplitudeImageFileNames.end());
00381                 std::sort(m_CoordinateImageFileNames.begin(),m_CoordinateImageFileNames.end());
00382                 std::sort(m_RangeImageFileNames.begin(),m_RangeImageFileNames.end());
00383                 std::cout << "INFO - VirtualRangeCam::Open:" << std::endl;
00384                 std::cout << "\t ... Extracted '" << intensityImageCounter[extInt] << "' intensity images (3*8 or 16 bit/value)\n";
00385                 std::cout << "\t ... Extracted '" << amplitudeImageCounter[extAmp] << "' amplitude images (16 bit/value)\n";
00386                 std::cout << "\t ... Extracted '" << coordinateImageCounter[extCoord] << "' coordinate images (3*16 bit/value)\n";
00387                 std::cout << "\t ... Extracted '" << rangeImageCounter[extRange] << "' range images (16 bit/value)\n";
00388 
00389                 if (intensityImageCounter[extInt] == 0 && amplitudeImageCounter[extAmp] == 0)
00390                 {
00391                         std::cerr << "ERROR - VirtualRangeCam::Open:" << std::endl;
00392                         std::cerr << "\t ... Could not detect any intensity or amplitude images" << std::endl;
00393                         std::cerr << "\t ... from the specified directory." << std::endl;
00394                         return ipa_CameraSensors::RET_FAILED;
00395                 }
00396 
00397                 if (coordinateImageCounter[extCoord] != 0 &&
00398                         ((intensityImageCounter[extInt] != coordinateImageCounter[extCoord] &&
00399                         amplitudeImageCounter[extAmp] != coordinateImageCounter[extCoord]) ||
00400                         (coordinateImageCounter[extCoord] != rangeImageCounter[extRange])))
00401                 {
00402                         std::cerr << "ERROR - VirtualRangeCam::Open:" << std::endl;
00403                         std::cerr << "\t ... Number of intensity, range and coordinate images must agree." << std::endl;
00404                         return ipa_CameraSensors::RET_FAILED;
00405                 }
00406 
00407                 if((m_CalibrationMethod == NATIVE || m_CalibrationMethod == MATLAB_NO_Z) && coordinateImageCounter[extCoord] == 0 )
00408                 {
00409                         std::cerr << "ERROR - VirtualRangeCam::Open:" << std::endl;
00410                         std::cerr << "\t ... Coordinate images must be available for calibration mode NATIVE or MATLAB_NO_Z." << std::endl;
00411                         return ipa_CameraSensors::RET_FAILED;
00412                 }
00413         }
00414         else
00415         {
00416                 std::cerr << "ERROR - VirtualRangeCam::Open():" << std::endl;
00417                 std::cerr << "\t ... Path '" << absoluteDirectoryName.file_string() << "' is not a directory." << std::endl;
00418                 return ipa_CameraSensors::RET_FAILED;
00419         }
00420 
00421 
00422         std::cout << "**************************************************" << std::endl;
00423         std::cout << "VirtualRangeCam::Open(): Virtual range camera OPEN" << std::endl;
00424         std::cout << "**************************************************" << std::endl<< std::endl;
00425         m_open = true;
00426 
00427         return RET_OK;
00428 }
00429 
00430 
00431 unsigned long VirtualRangeCam::Close()
00432 {
00433         if (!isOpen())
00434         {
00435                 return (RET_OK);
00436         }
00437 
00438         m_open = false;
00439         return RET_OK;
00440 
00441 }
00442 
00443 
00444 unsigned long VirtualRangeCam::SetProperty(t_cameraProperty* cameraProperty)
00445 {
00446         switch (cameraProperty->propertyID)
00447         {
00448                 case PROP_CAMERA_RESOLUTION:
00449 
00450                 default:
00451                         std::cerr << "ERROR - VirtualRangeCam::SetProperty:" << std::endl;
00452                         std::cerr << "\t ... Property " << cameraProperty->propertyID << " unspecified.\n";
00453                         return RET_FAILED;
00454                         break;
00455         }
00456 
00457         return RET_OK;
00458 }
00459 
00460 
00461 unsigned long VirtualRangeCam::SetPropertyDefaults()
00462 {
00463         return RET_FUNCTION_NOT_IMPLEMENTED;
00464 }
00465 
00466 
00467 unsigned long VirtualRangeCam::GetProperty(t_cameraProperty* cameraProperty)
00468 {
00469         switch (cameraProperty->propertyID)
00470         {
00471                 case PROP_CAMERA_RESOLUTION:
00472                         cameraProperty->cameraResolution.xResolution = m_ImageWidth;
00473                         cameraProperty->cameraResolution.yResolution = m_ImageHeight;
00474                         cameraProperty->propertyType = TYPE_CAMERA_RESOLUTION;
00475                         break;
00476 
00477                 case PROP_DMA_BUFFER_SIZE:
00478                         cameraProperty->u_integerData = m_BufferSize;
00479                         return RET_OK;
00480                         break;
00481 
00482                 default:
00483                         std::cerr << "VirtualRangeCam::GetProperty:" << std::endl;
00484                         std::cerr << "\t ... Property " << cameraProperty->propertyID << " unspecified.";
00485                         return RET_FAILED;
00486                         break;
00487 
00488         }
00489 
00490         return RET_OK;
00491 }
00492 
00493 
00494 // Wrapper for IplImage retrival from AcquireImage
00495 // Images have to be initialized prior to calling this function
00496 unsigned long VirtualRangeCam::AcquireImages(cv::Mat* rangeImage, cv::Mat* grayImage, cv::Mat* cartesianImage,
00497                                                                                          bool getLatestFrame, bool undistort, ipa_CameraSensors::t_ToFGrayImageType grayImageType)
00498 {
00499         //std::cout << m_ImageCounter << std::endl;
00500 
00501         char* rangeImageData = 0;
00502         char* grayImageData = 0;
00503         char* cartesianImageData = 0;
00504         int widthStepRange = -1;
00505         int widthStepGray = -1;
00506         int widthStepCartesian = -1;
00507 
00508         if(rangeImage)
00509         {
00510                 rangeImage->create(m_ImageHeight, m_ImageWidth, CV_32FC1);
00511                 rangeImageData = (char*) rangeImage->data;
00512                 widthStepRange = rangeImage->step;
00513         }
00514 
00515         if(grayImage)
00516         {
00517                 if (grayImageType == ipa_CameraSensors::INTENSITY_8U3) grayImage->create(m_ImageHeight, m_ImageWidth, CV_8UC3);
00518                 else grayImage->create(m_ImageHeight, m_ImageWidth, CV_32FC1);
00519                 grayImageData = (char*) grayImage->data;
00520                 widthStepGray = grayImage->step;
00521         }
00522 
00523         if(cartesianImage)
00524         {
00525                 cartesianImage->create(m_ImageHeight, m_ImageWidth, CV_32FC3);
00526                 cartesianImageData = (char*) cartesianImage->data;
00527                 widthStepCartesian = cartesianImage->step;
00528         }
00529 
00530         if (widthStepRange+widthStepGray+widthStepCartesian == -3)
00531         {
00532                 return RET_OK;
00533         }
00534 
00535         return AcquireImages(widthStepRange, widthStepGray, widthStepCartesian, rangeImageData, grayImageData, cartesianImageData, getLatestFrame, undistort, grayImageType);
00536 
00537 }
00538 
00539 unsigned long VirtualRangeCam::AcquireImages(int widthStepRange, int widthStepGray, int widthStepCartesian, char* rangeImageData, char* grayImageData, char* cartesianImageData,
00540                                                                                          bool getLatestFrame, bool undistort, ipa_CameraSensors::t_ToFGrayImageType grayImageType)
00541 {
00542         if (!m_open)
00543         {
00544                 std::cerr << "ERROR - VirtualRangeCam::AcquireImages:" << std::endl;
00545                 std::cerr << "\t ... Camera not open." << std::endl;
00546                 return (RET_FAILED | RET_CAMERA_NOT_OPEN);
00547         }
00548 
00550 // Range image (distorted or undistorted)
00552         if (rangeImageData)
00553         {
00554                 float* f_ptr = 0;
00555                 float* f_ptr_dst = 0;
00556                 bool releaseNecessary = false;
00557 
00558                 cv::Mat rangeMat;
00559                 IplImage rangeIpl;
00560                 IplImage* rangeImage = &rangeIpl;
00561                 if (m_RangeImageFileNames[m_ImageCounter].find(".bin") != std::string::npos)
00562                 {
00563                         ipa_Utils::LoadMat(rangeMat, m_RangeImageFileNames[m_ImageCounter]);
00564                         rangeIpl = (IplImage)rangeMat;
00565                 }
00566                 else if (m_RangeImageFileNames[m_ImageCounter].find(".xml") != std::string::npos)
00567                 {
00568                         rangeImage = (IplImage*) cvLoad(m_RangeImageFileNames[m_ImageCounter].c_str(), 0);
00569                         releaseNecessary = true;
00570                 }
00571                 else
00572                 {
00573                         std::cerr << "ERROR - VirtualRangeCam::AcquireImages:\n";
00574                         std::cerr << "\t ... Wrong file format for file " << m_RangeImageFileNames[m_ImageCounter] << ".\n";
00575                         CV_Assert(false);
00576                 }
00577 
00578                 if (!undistort)
00579                 {
00580                         // put data in corresponding IPLImage structures
00581                         for(unsigned int row=0; row<(unsigned int)m_ImageHeight; row++)
00582                         {
00583                                 f_ptr = (float*) (rangeImage->imageData + row*rangeImage->widthStep);
00584                                 f_ptr_dst = (float*) (rangeImageData + row*widthStepRange);
00585 
00586                                 for (unsigned int col=0; col<(unsigned int)m_ImageWidth; col++)
00587                                 {
00588                                         f_ptr_dst[col] = f_ptr[col];
00589                                 }
00590                         }
00591                 }
00592                 else
00593                 {
00594                         cv::Mat undistortedData (m_ImageHeight, m_ImageWidth, CV_32FC1, (float*) rangeImageData);
00595                         cv::Mat cpp_rangeImage = rangeImage;
00596 
00597                         assert (!m_undistortMapX.empty() && !m_undistortMapY.empty());
00598                         cv::remap(cpp_rangeImage, undistortedData, m_undistortMapX, m_undistortMapY, cv::INTER_LINEAR);
00599                 }
00600 
00601                 if (releaseNecessary) cvReleaseImage(&rangeImage);
00602         } // End if (rangeImage)
00604 // Gray image based on amplitude or intensity (distorted or undistorted)
00606         if(grayImageData)
00607         {
00608                 float* f_ptr = 0;
00609                 float* f_ptr_dst = 0;
00610                 unsigned char* uc_ptr = 0;
00611                 unsigned char* uc_ptr_dst = 0;
00612                 cv::Mat grayMat;
00613                 IplImage grayIpl;
00614                 IplImage* grayImage = &grayIpl;
00615                 bool releaseNecessary = false;
00616 
00617                 // load image
00618                 if ((grayImageType == ipa_CameraSensors::INTENSITY_32F1) || (grayImageType == ipa_CameraSensors::INTENSITY_8U3))
00619                 {
00620                         // intensity image
00621                         if (m_IntensityImageFileNames[m_ImageCounter].find(".bin") != std::string::npos)
00622                         {
00623                                 ipa_Utils::LoadMat(grayMat, m_IntensityImageFileNames[m_ImageCounter]);
00624                                 grayIpl = (IplImage)grayMat;
00625                         }
00626                         else if (m_IntensityImageFileNames[m_ImageCounter].find(".xml") != std::string::npos)
00627                         {
00628                                 grayImage = (IplImage*) cvLoad(m_IntensityImageFileNames[m_ImageCounter].c_str());
00629                                 releaseNecessary = true;
00630                         }
00631                         else if ((m_IntensityImageFileNames[m_ImageCounter].find(".png") != std::string::npos) || (m_IntensityImageFileNames[m_ImageCounter].find(".bmp") != std::string::npos) ||
00632                                         (m_IntensityImageFileNames[m_ImageCounter].find(".jpg") != std::string::npos))
00633                         {
00634                                 grayMat = cv::imread(m_IntensityImageFileNames[m_ImageCounter], -1);
00635                                 grayIpl = (IplImage)grayMat;
00636                         }
00637                         else
00638                         {
00639                                 std::cerr << "ERROR - VirtualRangeCam::AcquireImages:\n";
00640                                 std::cerr << "\t ... Wrong file format for file " << m_IntensityImageFileNames[m_ImageCounter] << ".\n";
00641                                 CV_Assert(false);
00642                         }
00643                 }
00644                 else
00645                 {
00646                         // amplitude image
00647                         if (m_AmplitudeImageFileNames[m_ImageCounter].find(".bin") != std::string::npos)
00648                         {
00649                                 ipa_Utils::LoadMat(grayMat, m_AmplitudeImageFileNames[m_ImageCounter]);
00650                                 grayIpl = (IplImage)grayMat;
00651                         }
00652                         else if (m_AmplitudeImageFileNames[m_ImageCounter].find(".xml") != std::string::npos)
00653                         {
00654                                 grayImage = (IplImage*) cvLoad(m_AmplitudeImageFileNames[m_ImageCounter].c_str());
00655                                 releaseNecessary = true;
00656                         }
00657                         else
00658                         {
00659                                 std::cerr << "ERROR - VirtualRangeCam::AcquireImages:\n";
00660                                 std::cerr << "\t ... Wrong file format for file " << m_AmplitudeImageFileNames[m_ImageCounter] << ".\n";
00661                                 CV_Assert(false);
00662                         }
00663                 }
00664 
00665                 // process image
00666                 if (!undistort)
00667                 {
00668                         if (grayImageType == ipa_CameraSensors::INTENSITY_8U3)
00669                         {
00670                                 for(unsigned int row=0; row<(unsigned int)m_ImageHeight; row++)
00671                                 {
00672                                         f_ptr = (float*) (grayImage->imageData + row*grayImage->widthStep);
00673                                         f_ptr_dst = (float*) (grayImageData + row*widthStepGray);
00674 
00675                                         for (unsigned int col=0; col<(unsigned int)m_ImageWidth; col++)
00676                                         {
00677                                                 f_ptr_dst[col] = f_ptr[col];
00678                                         }
00679                                 }
00680                         }
00681                         else
00682                         {
00683                                 for(unsigned int row=0; row<(unsigned int)m_ImageHeight; row++)
00684                                 {
00685                                         uc_ptr = (unsigned char*) (grayImage->imageData + row*grayImage->widthStep);
00686                                         uc_ptr_dst = (unsigned char*) (grayImageData + row*widthStepGray);
00687 
00688                                         for (unsigned int col=0; col<(unsigned int)m_ImageWidth; col++)
00689                                         {
00690                                                 uc_ptr_dst[col] = uc_ptr[col];
00691                                         }
00692                                 }
00693                         }
00694                 }
00695                 else
00696                 {
00697                         cv::Mat undistortedData;
00698                         if (grayImageType == ipa_CameraSensors::INTENSITY_8U3)
00699                         {
00700                                 undistortedData = cv::Mat(m_ImageHeight, m_ImageWidth, CV_8UC3, (unsigned char*) grayImageData);
00701                         }
00702                         else
00703                         {
00704                                 undistortedData = cv::Mat(m_ImageHeight, m_ImageWidth, CV_32FC1, (float*) grayImageData);
00705                         }
00706                         cv::Mat cpp_grayImage = grayImage;
00707 
00708                         assert (!m_undistortMapX.empty() && !m_undistortMapY.empty());
00709                         cv::remap(cpp_grayImage, undistortedData, m_undistortMapX, m_undistortMapY, cv::INTER_LINEAR);
00710                 }
00711 
00712                 if (releaseNecessary) cvReleaseImage(&grayImage);
00713         }
00715 // Cartesian image (always undistorted)
00717         if(cartesianImageData)
00718         {
00719                 float x = -1;
00720                 float y = -1;
00721                 float zCalibrated = -1;
00722                 float* f_ptr = 0;
00723                 float* f_ptr_dst = 0;
00724                 bool releaseNecessary = false;
00725 
00726                 if(m_CalibrationMethod==MATLAB)
00727                 {
00728                         CV_Assert(false);
00729                 }
00730                 else if(m_CalibrationMethod==MATLAB_NO_Z)
00731                 {
00732                         // XYZ image is assumed to be undistorted
00733                         // Unfortunately we have no access to the swissranger calibration
00734 
00735                         cv::Mat coordinateMat;
00736                         IplImage coordinateIpl;
00737                         IplImage* coordinateImage = &coordinateIpl;
00738                         if (m_CoordinateImageFileNames[m_ImageCounter].find(".bin") != std::string::npos)
00739                         {
00740                                 ipa_Utils::LoadMat(coordinateMat, m_CoordinateImageFileNames[m_ImageCounter]);
00741                                 coordinateIpl = (IplImage)coordinateMat;
00742                         }
00743                         else if (m_CoordinateImageFileNames[m_ImageCounter].find(".xml") != std::string::npos)
00744                         {
00745                                 coordinateImage = (IplImage*) cvLoad(m_CoordinateImageFileNames[m_ImageCounter].c_str(), 0);
00746                                 releaseNecessary = true;
00747                         }
00748                         else
00749                         {
00750                                 std::cerr << "ERROR - VirtualRangeCam::AcquireImages:\n";
00751                                 std::cerr << "\t ... Wrong file format for file " << m_CoordinateImageFileNames[m_ImageCounter] << ".\n";
00752                                 CV_Assert(false);
00753                         }
00754 
00755                         for(unsigned int row=0; row<(unsigned int)m_ImageHeight; row++)
00756                         {
00757                                 f_ptr = (float*) (coordinateImage->imageData + row*coordinateImage->widthStep);
00758                                 f_ptr_dst = (float*) (cartesianImageData + row*widthStepCartesian);
00759 
00760                                 for (unsigned int col=0; col<(unsigned int)m_ImageWidth; col++)
00761                                 {
00762                                         int colTimes3 = 3*col;
00763 
00764                                         zCalibrated = f_ptr[colTimes3+2];
00765                                         GetCalibratedXYMatlab(col, row, zCalibrated, x, y);
00766 
00767                                         f_ptr_dst[colTimes3] = x;
00768                                         f_ptr_dst[colTimes3 + 1] = y;
00769                                         f_ptr_dst[colTimes3 + 2] = zCalibrated;
00770 
00771                                         if (f_ptr_dst[colTimes3 + 2] < 0)
00772                                         {
00773                                                 std::cout << "<0: " << row << " " << col << "\n";
00774                                         }
00775                                 }
00776                         }
00777                         if (releaseNecessary) cvReleaseImage(&coordinateImage);
00778                 }
00779                 else if(m_CalibrationMethod==NATIVE)
00780                 {
00781                         cv::Mat coordinateMat;
00782                         IplImage coordinateIpl;
00783                         IplImage* coordinateImage = &coordinateIpl;
00784                         if (m_CoordinateImageFileNames[m_ImageCounter].find(".bin") != std::string::npos)
00785                         {
00786                                 ipa_Utils::LoadMat(coordinateMat, m_CoordinateImageFileNames[m_ImageCounter]);
00787                                 coordinateIpl = (IplImage)coordinateMat;
00788                         }
00789                         else if (m_CoordinateImageFileNames[m_ImageCounter].find(".xml") != std::string::npos)
00790                         {
00791                                 coordinateImage = (IplImage*) cvLoad(m_CoordinateImageFileNames[m_ImageCounter].c_str(), 0);
00792                                 releaseNecessary = true;
00793                         }
00794                         else
00795                         {
00796                                 std::cerr << "ERROR - VirtualRangeCam::AcquireImages:\n";
00797                                 std::cerr << "\t ... Wrong file format for file " << m_CoordinateImageFileNames[m_ImageCounter] << ".\n";
00798                                 CV_Assert(false);
00799                         }
00800 
00801                         for(unsigned int row=0; row<(unsigned int)m_ImageHeight; row++)
00802                         {
00803                                 f_ptr = (float*) (coordinateImage->imageData + row*coordinateImage->widthStep);
00804                                 f_ptr_dst = (float*) (cartesianImageData + row*widthStepCartesian);
00805 
00806                                 for (unsigned int col=0; col<(unsigned int)m_ImageWidth; col++)
00807                                 {
00808                                         int colTimes3 = 3*col;
00809 
00810                                         f_ptr_dst[colTimes3] =f_ptr[colTimes3+0];;
00811                                         f_ptr_dst[colTimes3 + 1] = f_ptr[colTimes3+1];
00812                                         f_ptr_dst[colTimes3 + 2] = f_ptr[colTimes3+2];
00813                                 }
00814                         }
00815                         if (releaseNecessary) cvReleaseImage(&coordinateImage);
00816                 }
00817                 else
00818                 {
00819                         std::cerr << "ERROR - VirtualRangeCam::AcquireImages:" << std::endl;
00820                         std::cerr << "\t ... Calibration method unknown.\n";
00821                         return RET_FAILED;
00822                 }
00823         }
00824 
00825         std::cout << m_ImageCounter << "        \r" << std::endl;
00826         m_ImageCounter++;
00827         if ((m_IntensityImageFileNames.size() != 0 && m_ImageCounter >= m_IntensityImageFileNames.size()) ||
00828                 (m_AmplitudeImageFileNames.size() != 0 && m_ImageCounter >= m_AmplitudeImageFileNames.size()) ||
00829                 (m_RangeImageFileNames.size() != 0 && m_ImageCounter >= m_RangeImageFileNames.size()) ||
00830                 (m_CoordinateImageFileNames.size() != 0 && m_ImageCounter >= m_CoordinateImageFileNames.size()))
00831         {
00832                 // Reset image counter
00833                 m_ImageCounter = 0;
00834         }
00835 
00836         return RET_OK;
00837 }
00838 
00839 int VirtualRangeCam::GetNumberOfImages()
00840 {
00841         if (m_IntensityImageFileNames.size() == 0 &&
00842                 m_AmplitudeImageFileNames.size() == 0 &&
00843                 m_RangeImageFileNames.size() == 0 &&
00844                 m_CoordinateImageFileNames.size() == 0)
00845         {
00846                 return 0;
00847         }
00848 
00849         int min=std::numeric_limits<int>::max();
00850 
00851         if (m_IntensityImageFileNames.size() != 0) min = (int)std::min((float)min, (float)m_IntensityImageFileNames.size());
00852         if (m_AmplitudeImageFileNames.size() != 0) min = (int)std::min((float)min, (float)m_AmplitudeImageFileNames.size());
00853         if (m_RangeImageFileNames.size() != 0) min = (int)std::min((float)min, (float)m_RangeImageFileNames.size());
00854         if (m_CoordinateImageFileNames.size() != 0) min = (int)std::min((float)min, (float)m_CoordinateImageFileNames.size());
00855 
00856         return min;
00857 }
00858 
00859 unsigned long VirtualRangeCam::SetPathToImages(std::string path)
00860 {
00861         m_CameraDataDirectory = path;
00862         return ipa_Utils::RET_OK;
00863 }
00864 
00865 unsigned long VirtualRangeCam::SaveParameters(const char* filename)
00866 {
00867         return RET_FUNCTION_NOT_IMPLEMENTED;
00868 }
00869 
00870 
00871 // Assert, that <code>m_CoeffsA.size()</code> and <code>m_CoeffsB.size()</code> is initialized
00872 // Before calling <code>GetCalibratedZMatlab</code>
00873 unsigned long VirtualRangeCam::GetCalibratedZMatlab(int u, int v, float zRaw, float& zCalibrated)
00874 {
00875         double c[7] = {m_CoeffsA0.at<double>(v,u), m_CoeffsA1.at<double>(v,u), m_CoeffsA2.at<double>(v,u),
00876                 m_CoeffsA3.at<double>(v,u), m_CoeffsA4.at<double>(v,u), m_CoeffsA5.at<double>(v,u), m_CoeffsA6.at<double>(v,u)};
00877         double y = 0;
00878 
00879         ipa_Utils::EvaluatePolynomial((double) zRaw, 6, &c[0], &y);
00880 
00881         zCalibrated = (float) y;
00882         return RET_OK;
00883 }
00884 
00885 unsigned long VirtualRangeCam::GetCalibratedXYMatlab(int u, int v, float z, float& x, float& y)
00886 {
00887         // Conversion form m to mm
00888         z *= 1000;
00889 
00890         // Use intrinsic camera parameters
00891         double fx, fy, cx, cy;
00892 
00893         fx = m_intrinsicMatrix.at<double>(0, 0);
00894         fy = m_intrinsicMatrix.at<double>(1, 1);
00895 
00896         cx = m_intrinsicMatrix.at<double>(0, 2);
00897         cy = m_intrinsicMatrix.at<double>(1, 2);
00898 
00899         // Fundamental equation: u = (fx*x)/z + cx
00900         if (fx == 0)
00901         {
00902                 std::cerr << "VirtualRangeCam::GetCalibratedXYMatlab:" << std::endl;
00903                 std::cerr << "\t ... fx is 0.\n";
00904                 return RET_FAILED;
00905         }
00906         x = (float) (z*(u-cx)/fx) ;
00907 
00908         // Fundamental equation: v = (fy*y)/z + cy
00909         if (fy == 0)
00910         {
00911                 std::cerr << "VirtualRangeCam::GetCalibratedXYMatlab:" << std::endl;
00912                 std::cerr << "\t ... fy is 0.\n";
00913                 return RET_FAILED;
00914         }
00915         y = (float) (z*(v-cy)/fy);
00916 
00917         // Conversion from mm to m
00918         x /= 1000;
00919         y /= 1000;
00920 
00921         return RET_OK;
00922 }
00923 
00924 unsigned long VirtualRangeCam::GetCalibratedUV(double x, double y, double z, double& u, double& v)
00925 {
00926         if(m_CalibrationMethod==MATLAB || m_CalibrationMethod==MATLAB_NO_Z)
00927         {
00928                 double fx, fy, cx, cy;
00929                 fx = m_intrinsicMatrix.at<double>(0, 0);
00930                 fy = m_intrinsicMatrix.at<double>(1, 1);
00931 
00932                 cx = m_intrinsicMatrix.at<double>(0, 2);
00933                 cy = m_intrinsicMatrix.at<double>(1, 2);
00934 
00935                 // Conversion from m to mm
00936                 x *= 1000;
00937                 y *= 1000;
00938                 z *= 1000;
00939 
00940                 // Fundamental equation: u = (fx*x)/z + cx
00941                 if (z == 0)
00942                 {
00943                         std::cerr << "ERROR - VirtualRangeCam::GetCalibratedUV:" << std::endl;
00944                         std::cerr << "\t ... z is 0.\n";
00945                         return RET_FAILED;
00946                 }
00947 
00948                 u = (fx*x)/z + cx;
00949                 v = (fy*y)/z + cy;
00950         }
00951         else if(m_CalibrationMethod==NATIVE)
00952         {
00953                 // implement me
00954                 std::cerr << "ERROR - VirtualRangeCam::GetCalibratedUV:" << std::endl;
00955                 std::cerr << "\t ... Function not implemented.\n";
00956                 return RET_FAILED;
00957         }
00958 
00959         // Maybe skip this part... JBK skipped this - the calling function has to check!!
00960 
00961         if(u<0) u=0;
00962         if(u>=m_ImageWidth) u=m_ImageWidth-1;
00963         if(v<0) v=0;
00964         if(v>=m_ImageHeight) v=m_ImageHeight-1;
00965 
00966         return RET_OK;
00967 }
00968 
00969 unsigned long VirtualRangeCam::LoadParameters(const char* filename, int cameraIndex)
00970 {
00971         // Load SwissRanger parameters.
00972         boost::shared_ptr<TiXmlDocument> p_configXmlDocument (new TiXmlDocument( filename ));
00973 
00974         if (!p_configXmlDocument->LoadFile())
00975         {
00976                 std::cerr << "ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
00977                 std::cerr << "\t ... Error while loading xml configuration file" << std::endl;
00978                 std::cerr << "\t ...(Check filename and syntax):" << std::endl;
00979                 std::cerr << "\t ... " << filename << std::endl;
00980                 return (RET_FAILED | RET_FAILED_OPEN_FILE);
00981         }
00982         std::cout << "INFO - VirtualRangeCam::LoadParameters:" << std::endl;
00983         std::cout << "\t ... Parsing xml configuration file" << std::endl;
00984         std::cout << "\t ... '" << filename << "'" << std::endl;
00985 
00986         if ( p_configXmlDocument )
00987         {
00988 
00989 //************************************************************************************
00990 //      BEGIN LibCameraSensors
00991 //************************************************************************************
00992                 // Tag element "LibCameraSensors" of Xml Inifile
00993                 TiXmlElement *p_xmlElement_Root = NULL;
00994                 p_xmlElement_Root = p_configXmlDocument->FirstChildElement( "LibCameraSensors" );
00995 
00996                 if ( p_xmlElement_Root )
00997                 {
00998 
00999 //************************************************************************************
01000 //      BEGIN LibCameraSensors->VirtualRangeCam
01001 //************************************************************************************
01002                         // Tag element "VirtualRangeCam" of Xml Inifile
01003                         TiXmlElement *p_xmlElement_Root_VirtualRangeCam = NULL;
01004                         std::stringstream ss;
01005                         ss << "VirtualRangeCam_" << cameraIndex;
01006                         p_xmlElement_Root_VirtualRangeCam = p_xmlElement_Root->FirstChildElement( ss.str() );
01007                         if ( p_xmlElement_Root_VirtualRangeCam )
01008                         {
01009 
01010 //************************************************************************************
01011 //      BEGIN LibCameraSensors->VirtualRangeCam->CameraDataDirectory
01012 //************************************************************************************
01013                                 // Subtag element "IntrinsicParameters" of Xml Inifile
01014                                 TiXmlElement *p_xmlElement_Child = NULL;
01015                                 p_xmlElement_Child = p_xmlElement_Root_VirtualRangeCam->FirstChildElement( "CameraDataDirectory" );
01016                                 if ( p_xmlElement_Child )
01017                                 {
01018                                         // read and save value of attribute
01019                                         std::string tempString;
01020                                         if ( p_xmlElement_Child->QueryValueAttribute( "relativePath", &tempString ) != TIXML_SUCCESS)
01021                                         {
01022                                                 std::cerr << "ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
01023                                                 std::cerr << "\t ... Can't find attribute 'relativePath' of tag 'CameraDataDirectory'." << std::endl;
01024                                                 return (RET_FAILED | RET_XML_ATTR_NOT_FOUND);
01025                                         }
01026 
01027                                         m_CameraDataDirectory = m_CameraDataDirectory + tempString + "/";
01028                                 }
01029                                 else
01030                                 {
01031                                         std::cerr << "ERROR - VirtualColorCam::LoadParameters:" << std::endl;
01032                                         std::cerr << "\t ... Can't find tag 'CameraDataDirectory'." << std::endl;
01033                                         return (RET_FAILED | RET_XML_TAG_NOT_FOUND);
01034                                 }
01035 
01036 //************************************************************************************
01037 //      BEGIN LibCameraSensors->VirtualRangeCam->CalibrationMethod
01038 //************************************************************************************
01039                                 // Subtag element "OperationMode" of Xml Inifile
01040                                 p_xmlElement_Child = NULL;
01041                                 p_xmlElement_Child = p_xmlElement_Root_VirtualRangeCam->FirstChildElement( "CalibrationMethod" );
01042                                 std::string tempString;
01043                                 if ( p_xmlElement_Child )
01044                                 {
01045                                         // read and save value of attribute
01046                                         if ( p_xmlElement_Child->QueryValueAttribute( "name", &tempString ) != TIXML_SUCCESS)
01047                                         {
01048                                                 std::cerr << "ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
01049                                                 std::cerr << "\t ... Can't find attribute 'name' of tag 'CalibrationMethod'." << std::endl;
01050                                                 return (RET_FAILED | RET_XML_ATTR_NOT_FOUND);
01051                                         }
01052                                         if (tempString == "MATLAB") m_CalibrationMethod = MATLAB;
01053                                         else if (tempString == "MATLAB_NO_Z") m_CalibrationMethod = MATLAB_NO_Z;
01054                                         else if (tempString == "NATIVE") m_CalibrationMethod = NATIVE;
01055                                         else
01056                                         {
01057                                                 std::cerr << "ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
01058                                                 std::cerr << "\t ... Calibration mode " << tempString << " unspecified." << std::endl;
01059                                                 return (RET_FAILED);
01060                                         }
01061                                 }
01062                                 else
01063                                 {
01064                                         std::cerr << "ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
01065                                         std::cerr << "\t ... Can't find tag 'CalibrationMethod'." << std::endl;
01066                                         return (RET_FAILED | RET_XML_TAG_NOT_FOUND);
01067                                 }
01068                         }
01069 //************************************************************************************
01070 //      END LibCameraSensors->VirtualRangeCam
01071 //************************************************************************************
01072                         else
01073                         {
01074                                 std::cerr << "ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
01075                                 std::cerr << "\t ... Can't find tag '" << ss.str() << "'" << std::endl;
01076                                 return (RET_FAILED | RET_XML_TAG_NOT_FOUND);
01077                         }
01078                 }
01079 
01080 //************************************************************************************
01081 //      END LibCameraSensors
01082 //************************************************************************************
01083                 else
01084                 {
01085                         std::cerr << "ERROR - VirtualRangeCam::LoadParameters:" << std::endl;
01086                         std::cerr << "\t ... Can't find tag 'LibCameraSensors'." << std::endl;
01087                         return (RET_FAILED | RET_XML_TAG_NOT_FOUND);
01088                 }
01089         }
01090 
01091         std::cout << "\t ... Parsing xml calibration file ... [OK] \n";
01092 
01093         return RET_OK;
01094 }


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