OpenCVCapture.cpp
Go to the documentation of this file.
00001 // ****************************************************************************
00002 // This file is part of the Integrating Vision Toolkit (IVT).
00003 //
00004 // The IVT is maintained by the Karlsruhe Institute of Technology (KIT)
00005 // (www.kit.edu) in cooperation with the company Keyetech (www.keyetech.de).
00006 //
00007 // Copyright (C) 2014 Karlsruhe Institute of Technology (KIT).
00008 // All rights reserved.
00009 //
00010 // Redistribution and use in source and binary forms, with or without
00011 // modification, are permitted provided that the following conditions are met:
00012 //
00013 // 1. Redistributions of source code must retain the above copyright
00014 //    notice, this list of conditions and the following disclaimer.
00015 //
00016 // 2. Redistributions in binary form must reproduce the above copyright
00017 //    notice, this list of conditions and the following disclaimer in the
00018 //    documentation and/or other materials provided with the distribution.
00019 //
00020 // 3. Neither the name of the KIT nor the names of its contributors may be
00021 //    used to endorse or promote products derived from this software
00022 //    without specific prior written permission.
00023 //
00024 // THIS SOFTWARE IS PROVIDED BY THE KIT AND CONTRIBUTORS “AS IS” AND ANY
00025 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00026 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00027 // DISCLAIMED. IN NO EVENT SHALL THE KIT OR CONTRIBUTORS BE LIABLE FOR ANY
00028 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00029 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00031 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00032 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00033 // THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00034 // ****************************************************************************
00035 
00036 
00037 
00038 // ****************************************************************************
00039 // Includes
00040 // ****************************************************************************
00041 
00042 #include "OpenCVCapture.h"
00043 #include "Image/ImageProcessor.h"
00044 #include "Image/ByteImage.h"
00045 
00046 
00047 
00048 // ****************************************************************************
00049 // Constructor / Destructor
00050 // ****************************************************************************
00051 
00052 COpenCVCapture::COpenCVCapture(int nIndex, const char *pFilename) : m_nIndex(nIndex)
00053 {
00054         m_pCapture = 0;
00055         m_pIplImage = 0;
00056 
00057         m_sFilename = "";
00058 
00059         if (pFilename)
00060                 m_sFilename += pFilename;
00061 }
00062 
00063 COpenCVCapture::~COpenCVCapture()
00064 {
00065         CloseCamera();
00066 }
00067 
00068 
00069 // ****************************************************************************
00070 // Methods
00071 // ****************************************************************************
00072 
00073 bool COpenCVCapture::OpenCamera()
00074 {
00075         CloseCamera();
00076 
00077         if (m_sFilename.length() > 0)
00078                 m_pCapture = cvCaptureFromFile(m_sFilename.c_str());
00079         else
00080                 m_pCapture = cvCaptureFromCAM(m_nIndex);
00081         if (!m_pCapture)
00082                 return false;
00083 
00084         cvSetCaptureProperty(m_pCapture, CV_CAP_PROP_FPS, 30);
00085         cvSetCaptureProperty(m_pCapture, CV_CAP_PROP_FRAME_WIDTH, 640);
00086         cvSetCaptureProperty(m_pCapture, CV_CAP_PROP_FRAME_HEIGHT, 480);
00087 
00088         m_pIplImage = cvQueryFrame(m_pCapture);
00089         
00090         return true;
00091 }
00092 
00093 void COpenCVCapture::CloseCamera()
00094 {
00095         cvReleaseCapture(&m_pCapture);
00096         m_pIplImage = 0;
00097 }
00098 
00099 bool COpenCVCapture::CaptureImage(CByteImage **ppImages)
00100 {
00101         m_pIplImage = cvQueryFrame(m_pCapture);
00102         if (!m_pIplImage)
00103                 return false;
00104 
00105         CByteImage *pImage = ppImages[0];
00106         if (!pImage || pImage->width != m_pIplImage->width || pImage->height != m_pIplImage->height)
00107                 return false;
00108 
00109         if (m_pIplImage->depth != IPL_DEPTH_8U)
00110                 return false;
00111         else if (m_pIplImage->nChannels != 1 && m_pIplImage->nChannels != 3)
00112                 return false;
00113         else if (m_pIplImage->nChannels == 1 && pImage->type != CByteImage::eGrayScale)
00114                 return false;
00115         else if (m_pIplImage->nChannels == 3 && pImage->type != CByteImage::eRGB24)
00116                 return false;
00117         
00118         const int nBytes = pImage->width * pImage->height * pImage->bytesPerPixel;
00119         unsigned char *input = (unsigned char *) m_pIplImage->imageData;
00120         unsigned char *output = pImage->pixels;
00121 
00122         if (pImage->type == CByteImage::eGrayScale)
00123         {
00124                 memcpy(output, input, nBytes);
00125         }
00126         else if (pImage->type == CByteImage::eRGB24)
00127         {
00128                 for (int i = 0; i < nBytes; i += 3)
00129                 {
00130                         output[i] = input[i + 2];
00131                         output[i + 1] = input[i + 1];
00132                         output[i + 2] = input[i];
00133                 }
00134         }
00135 
00136         #ifdef WIN32
00137         ImageProcessor::FlipY(pImage, pImage);
00138         #endif
00139         
00140         return true;
00141 }
00142 
00143 
00144 int COpenCVCapture::GetWidth()
00145 {
00146         return m_pIplImage ? m_pIplImage->width : -1;
00147 }
00148 
00149 int COpenCVCapture::GetHeight()
00150 {
00151         return m_pIplImage ? m_pIplImage->height : -1;
00152 }
00153 
00154 CByteImage::ImageType COpenCVCapture::GetType()
00155 {
00156         return m_pIplImage ? (m_pIplImage->nChannels == 3 ? CByteImage::eRGB24 : CByteImage::eGrayScale) : (CByteImage::ImageType) -1;
00157 }


asr_ivt
Author(s): Allgeyer Tobias, Hutmacher Robin, Kleinert Daniel, Meißner Pascal, Scholz Jonas, Stöckle Patrick
autogenerated on Thu Jun 6 2019 21:46:57