VirtualRangeCam.h
Go to the documentation of this file.
00001 /****************************************************************
00002 *
00003 * Copyright (c) 2010
00004 *
00005 * Fraunhofer Institute for Manufacturing Engineering
00006 * and Automation (IPA)
00007 *
00008 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00009 *
00010 * Project name: care-o-bot
00011 * ROS stack name: cob_driver
00012 * ROS package name: cob_camera_sensors
00013 * Description: Virtual range camera representation.
00014 *
00015 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00016 *
00017 * Author: Jan Fischer, email:jan.fischer@ipa.fhg.de
00018 * Supervised by: Jan Fischer, email:jan.fischer@ipa.fhg.de
00019 *
00020 * Date of creation: Jan 2009
00021 * ToDo:
00022 *
00023 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00024 *
00025 * Redistribution and use in source and binary forms, with or without
00026 * modification, are permitted provided that the following conditions are met:
00027 *
00028 * * Redistributions of source code must retain the above copyright
00029 * notice, this list of conditions and the following disclaimer.
00030 * * Redistributions in binary form must reproduce the above copyright
00031 * notice, this list of conditions and the following disclaimer in the
00032 * documentation and/or other materials provided with the distribution.
00033 * * Neither the name of the Fraunhofer Institute for Manufacturing
00034 * Engineering and Automation (IPA) nor the names of its
00035 * contributors may be used to endorse or promote products derived from
00036 * this software without specific prior written permission.
00037 *
00038 * This program is free software: you can redistribute it and/or modify
00039 * it under the terms of the GNU Lesser General Public License LGPL as
00040 * published by the Free Software Foundation, either version 3 of the
00041 * License, or (at your option) any later version.
00042 *
00043 * This program is distributed in the hope that it will be useful,
00044 * but WITHOUT ANY WARRANTY; without even the implied warranty of
00045 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00046 * GNU Lesser General Public License LGPL for more details.
00047 *
00048 * You should have received a copy of the GNU Lesser General Public
00049 * License LGPL along with this program.
00050 * If not, see <http://www.gnu.org/licenses/>.
00051 *
00052 ****************************************************************/
00053 
00058 
00059 #ifndef __IPA_VIRTUALRANGECAM_H__
00060 #define __IPA_VIRTUALRANGECAM_H__
00061 
00062 #include "StdAfx.h"
00063 
00064 #ifdef __LINUX__
00065         #include <cob_camera_sensors/AbstractRangeImagingSensor.h>
00066 #else
00067         #include <cob_driver/cob_camera_sensors/common/include/cob_camera_sensors/AbstractRangeImagingSensor.h>
00068 #endif
00069 
00070 #include <stdio.h>
00071 #include <math.h>
00072 #include <assert.h>
00073 #include <sstream>
00074 
00075 #include <boost/filesystem.hpp>
00076 
00077 namespace ipa_CameraSensors {
00078 
00079 static const int SWISSRANGER_COLUMNS = 176;
00080 static const int SWISSRANGER_ROWS = 144;
00081 
00086 class __DLL_LIBCAMERASENSORS__ VirtualRangeCam : public AbstractRangeImagingSensor
00087 {
00088 public:
00089 
00090         VirtualRangeCam();
00091         ~VirtualRangeCam();
00092 
00093         //*******************************************************************************
00094         // AbstractRangeImagingSensor interface implementation
00095         //*******************************************************************************
00096 
00097         unsigned long Init(std::string directory, int cameraIndex = 0);
00098 
00099         unsigned long Open();
00100         unsigned long Close();
00101 
00102         unsigned long SetProperty(t_cameraProperty* cameraProperty);
00103         unsigned long SetPropertyDefaults();
00104         unsigned long GetProperty(t_cameraProperty* cameraProperty);
00105 
00106         unsigned long AcquireImages(int widthStepRange, int widthStepGray, int widthStepCartesian, char* rangeImage=NULL, char* intensityImage=NULL,
00107                 char* cartesianImage=NULL, bool getLatestFrame=true, bool undistort=true,
00108                 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1);
00109         unsigned long AcquireImages(cv::Mat* rangeImage = 0, cv::Mat* intensityImage = 0,
00110                 cv::Mat* cartesianImage = 0, bool getLatestFrame = true, bool undistort = true,
00111                 ipa_CameraSensors::t_ToFGrayImageType grayImageType = ipa_CameraSensors::INTENSITY_32F1);
00112 
00113         unsigned long GetCalibratedUV(double x, double y, double z, double& u, double& v);
00114 
00115         unsigned long SaveParameters(const char* filename);
00116 
00117         bool isInitialized() {return m_initialized;}
00118         bool isOpen() {return m_open;}
00119 
00122         int GetNumberOfImages();
00123 
00128         unsigned long SetPathToImages(std::string path);
00129 
00130 private:
00131         //*******************************************************************************
00132         // Camera specific members
00133         //*******************************************************************************
00134 
00137         inline void UpdateImageDimensionsOnFirstImage(std::string filename, std::string ext=".xml");
00138 
00143         inline void FindSourceImageFormat(std::map<std::string, int>::iterator& itCounter, std::string& ext);
00144 
00145         unsigned long GetCalibratedZMatlab(int u, int v, float zRaw, float& zCalibrated);
00146         unsigned long GetCalibratedXYMatlab(int u, int v, float z, float& x, float& y);
00147         
00153         unsigned long LoadParameters(const char* filename, int cameraIndex);
00154 
00155         bool m_CoeffsInitialized;
00156 
00161         cv::Mat m_CoeffsA0; 
00162         cv::Mat m_CoeffsA1; 
00163         cv::Mat m_CoeffsA2; 
00164         cv::Mat m_CoeffsA3; 
00165         cv::Mat m_CoeffsA4; 
00166         cv::Mat m_CoeffsA5; 
00167         cv::Mat m_CoeffsA6; 
00168 
00169         std::string m_CameraDataDirectory; 
00170         int m_CameraIndex; 
00171 
00172         std::vector<std::string> m_AmplitudeImageFileNames;
00173         std::vector<std::string> m_IntensityImageFileNames;
00174         std::vector<std::string> m_RangeImageFileNames ;
00175         std::vector<std::string> m_CoordinateImageFileNames ;
00176 
00177         int m_ImageWidth;  
00178         int m_ImageHeight; 
00179 
00180         double m_k1, m_k2, m_p1, m_p2; 
00181 };
00182 
00185 __DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_VirtualCam();
00186 
00187 } // end namespace ipa_CameraSensors
00188 #endif // __IPA_VIRTUALRANGECAM_H__
00189 
00190 


cob_camera_sensors
Author(s): Jan Fischer
autogenerated on Sun Oct 5 2014 23:07:54