CVCamCapture.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 // Filename:  CVCamCapture.cpp
00037 // Author:    Pedram Azad
00038 // Date:      2005
00039 // ****************************************************************************
00040 
00041 
00042 // ****************************************************************************
00043 // Includes
00044 // ****************************************************************************
00045 
00046 #include "CVCamCapture.h"
00047 
00048 #include "Image/ByteImage.h"
00049 #include "Image/IplImageAdaptor.h"
00050 #include "Image/ImageProcessor.h"
00051 #include "Threading/Mutex.h"
00052 
00053 #include <cvcam.h>
00054 #include <highgui.h>
00055 #include <cv.h>
00056 
00057 #include <memory.h>
00058 
00059 
00060 
00061 // ****************************************************************************
00062 // Global and static variables
00063 // ****************************************************************************
00064 
00065 CMutex cvcam_critical_section;
00066 static CByteImage *pCapturedImage = 0;
00067 static bool bFirstFrame = false;
00068 
00069 
00070 // ****************************************************************************
00071 // Static methods
00072 // ****************************************************************************
00073 
00074 static void callback(IplImage *pIplImage)
00075 {
00076         if (!pIplImage)
00077                 return;
00078 
00079         CByteImage *pImage = IplImageAdaptor::Adapt(pIplImage);
00080 
00081 
00082         cvcam_critical_section.Lock();
00083 
00084         if (pCapturedImage && (pCapturedImage->width != pImage->width || pCapturedImage->height != pImage->height || pCapturedImage->type != pImage->type))
00085         {
00086                 delete pCapturedImage;
00087                 pCapturedImage = 0;
00088         }
00089 
00090         if (!pCapturedImage)
00091                 pCapturedImage = new CByteImage(pImage);
00092 
00093         unsigned char *input = pImage->pixels;
00094         unsigned char *output = pCapturedImage->pixels;
00095         const int nBytes = pImage->width * pImage->height * pImage->bytesPerPixel;
00096 
00097         if (pImage->type == CByteImage::eRGB24)
00098         {
00099                 for (int i = 0; i < nBytes; i += 3)
00100                 {
00101                         output[i] = input[i + 2];
00102                         output[i + 1] = input[i + 1];
00103                         output[i + 2] = input[i];
00104                 }
00105         }
00106         else if (pImage->type == CByteImage::eGrayScale)
00107         {
00108                 memcpy(output, input, nBytes);
00109         }
00110 
00111         #ifdef WIN32
00112         ImageProcessor::FlipY(pCapturedImage, pCapturedImage);
00113         #endif
00114 
00115         cvcam_critical_section.UnLock();
00116 
00117         bFirstFrame = true;
00118 
00119         delete pImage;
00120 }
00121 
00122 
00123 // ****************************************************************************
00124 // Constructor / Destructor
00125 // ****************************************************************************
00126 
00127 CCVCamCapture::CCVCamCapture()
00128 {
00129         m_bStarted = false;
00130 
00131         m_pImage = 0;
00132         pCapturedImage = 0;
00133 }
00134 
00135 CCVCamCapture::~CCVCamCapture()
00136 {
00137         CloseCamera();
00138 
00139         if (m_pImage)
00140         {
00141                 delete m_pImage;
00142                 delete pCapturedImage;
00143         }
00144 }
00145 
00146 
00147 // ****************************************************************************
00148 // Methods
00149 // ****************************************************************************
00150 
00151 bool CCVCamCapture::OpenCamera()
00152 {
00153         if (m_bStarted)
00154                 return true;
00155 
00156         m_bStarted = false;
00157 
00158         if (cvcamGetCamerasCount() <=  0)
00159                 return false;
00160 
00161         // selects the 1st found camera
00162         cvcamSetProperty(0, CVCAM_PROP_ENABLE, CVCAMTRUE);  
00163         cvcamSetProperty(0, CVCAM_PROP_RENDER, CVCAMTRUE);      
00164         // set up a callback to process the frames
00165         cvcamSetProperty(0, CVCAM_PROP_CALLBACK, (void*) callback);
00166         // start the camera
00167         cvcamInit();
00168         cvcamStart();
00169 
00170         m_bStarted = true;
00171 
00172         while (!bFirstFrame)
00173                 cvWaitKey(10);
00174 
00175         return true;
00176 }
00177 
00178 void CCVCamCapture::CloseCamera()
00179 {
00180         cvcamStop();
00181         cvcamExit();
00182         m_bStarted = false;
00183         bFirstFrame = false;
00184 }
00185 
00186 bool CCVCamCapture::CaptureImage(CByteImage **ppImages)
00187 {
00188         if (!ppImages || !ppImages[0])
00189                 return false;
00190 
00191         CByteImage *pImage = ppImages[0];
00192 
00193         cvcam_critical_section.Lock();
00194         
00195         if (!pCapturedImage)
00196         {
00197                 cvcam_critical_section.UnLock();
00198                 return false;
00199         }
00200         
00201         // check if input image matches format
00202         if (pCapturedImage->width != pImage->width || pCapturedImage->height != pImage->height || pCapturedImage->type != pImage->type)
00203         {
00204                 cvcam_critical_section.UnLock();
00205                 return false;
00206         }
00207         
00208         ImageProcessor::CopyImage(pCapturedImage, pImage);
00209 
00210         cvcam_critical_section.UnLock();
00211 
00212         return true;
00213 }
00214 
00215 int CCVCamCapture::GetWidth()
00216 {
00217         return pCapturedImage ? pCapturedImage->width : -1;
00218 }
00219 
00220 int CCVCamCapture::GetHeight()
00221 {
00222         return pCapturedImage ? pCapturedImage->height : -1;
00223 }
00224 
00225 CByteImage::ImageType CCVCamCapture::GetType()
00226 {
00227         return pCapturedImage ? pCapturedImage->type : (CByteImage::ImageType) -1;
00228 }


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