Linux1394Capture.h
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:  Linux1394Capture.h
00037 // Author:    Pedram Azad, Kai Welke
00038 // Date:      2005
00039 // ****************************************************************************
00040 // Changes:   24.08.2006, Kai Welke
00041 //            * Added YUV411 support
00042 //            25.09.2006, Kai Welke
00043 //            * Added support for UIDs and different frame rates
00044 // ****************************************************************************
00045 
00046 
00047 #ifndef _LINUX_1394_CAPTURE_H_
00048 #define _LINUX_1394_CAPTURE_H_
00049 
00050 
00051 // ****************************************************************************
00052 // Necessary includes
00053 // ****************************************************************************
00054 
00055 #include "Interfaces/VideoCaptureInterface.h"
00056 #include "Image/ImageProcessor.h"
00057 #include <string>
00058 
00059 #include <libraw1394/raw1394.h>
00060 #include <libdc1394/dc1394_control.h>
00061 
00062 
00063 
00064 // ****************************************************************************
00065 // Forward declarations
00066 // ****************************************************************************
00067 
00068 class CByteImage;
00069 
00070 
00071 // ****************************************************************************
00072 // Defines
00073 // ****************************************************************************
00074 
00075 #define MAX_CAMERAS 4 // don't set this smaller than 2
00076 #define MAX_PORTS 4
00077 
00078 
00079 
00080 
00081 // ****************************************************************************
00082 // CLinux1394Capture
00083 // ****************************************************************************
00084 
00085 class CLinux1394Capture : public CVideoCaptureInterface
00086 {
00087 public:
00088         // constructor, variable arguments are camera uids as const char*
00089         CLinux1394Capture(int nCameras, VideoMode mode, ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType = ImageProcessor::eBayerRG, FrameRate frameRate = e30fps); 
00090         CLinux1394Capture(VideoMode mode, ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType = ImageProcessor::eBayerRG, FrameRate frameRate = e30fps, int nNumberUIDs = 0, ...);
00091         
00092         // format 7 modes
00093         CLinux1394Capture(int nCameras, VideoMode mode, int nFormat7PacketSize = -1, int nFormat7MinX = 0, int nFormat7MinY = 0, int nFormat7Width = 640, int nFormat7Height = 480,
00094         ColorMode colorMode = CVideoCaptureInterface::eBayerPatternToRGB24, ImageProcessor::BayerPatternType bayerPatternType = ImageProcessor::eBayerRG);
00095         
00096         CLinux1394Capture(VideoMode mode, int nFormat7PacketSize = -1, int nFormat7MinX = 0, int nFormat7MinY = 0, int nFormat7Width = 640, int nFormat7Height = 480,
00097         ColorMode colorMode = CVideoCaptureInterface::eBayerPatternToRGB24, ImageProcessor::BayerPatternType bayerPatternType = ImageProcessor::eBayerRG, int nNumberUIDs = 0, ...);
00098         
00099         
00100         // destructor
00101         ~CLinux1394Capture();
00102 
00103 
00104         // public methods
00105         bool OpenCamera();
00106         void CloseCamera();
00107         bool CaptureImage(CByteImage **ppImages);
00108         bool CaptureBayerPatternImage(CByteImage **ppImages);
00109         
00110         void SetGain(unsigned int nValue);
00111         void SetExposure(unsigned int nValue);
00112         void SetShutter(unsigned int nValue);
00113 
00114         int GetWidth() { return width; }
00115         int GetHeight() { return height; }
00116         CByteImage::ImageType GetType();
00117         int GetNumberOfCameras() { return m_nCameras; }
00118 
00119         
00120 private:
00121         struct TCameraInfo
00122         {
00123                 int     nPort;
00124                 int     nIndex;
00125                 std::string sUID;
00126         };
00127         
00128         // private methods
00129         bool OpenCamera(int nCamera);
00130         bool InitCameraMode();
00131         int GetDCFrameRateMode(FrameRate frameRate);
00132 
00133         // conversion
00134         void ConvertYUV411(CByteImage* pInput, CByteImage* pOutput);
00135         void YUVToRGB(int y, int u, int v, unsigned char* output);
00136 
00137         // multiple camera handling
00138         bool ListCameras();
00139         std::string CamUIDToString(unsigned int nLow, unsigned int nHigh);
00140         
00141         // private attributes
00142         // temporary images for capruting
00143         CByteImage *m_pTempImageHeader;
00144         CByteImage *m_pTempImage;
00145         
00146         int m_nPorts;
00147         int m_nMode;
00148 
00149         int width;
00150         int height;
00151         
00152         // number of cameras requested by user
00153         int m_nCameras;
00154         // requested video mode (see VideoCaptureInterface.h)
00155         const VideoMode m_mode;
00156         // requested color mode (see VideoCaptureInterface.h)
00157         const ColorMode m_colorMode;
00158         // requested frame rate (see VideoCaptureInterface.h)
00159         FrameRate m_frameRate;
00160         // requested bayer pattern type (see ImageProcessor.h)
00161         const ImageProcessor::BayerPatternType m_bayerPatternType;
00162         // unique camera ids as requested by user
00163         std::string m_sCameraUID[MAX_CAMERAS];
00164         bool m_bUseUIDs;
00165         // opened camera ids
00166         int m_nOpenedCameras[MAX_CAMERAS];
00167         // video mode
00168         int m_video_mode;
00169         // format 7 mode
00170         bool m_bFormat7Mode;
00171         int m_nFormat7PacketSize;
00172         int m_nFormat7MinX;
00173         int m_nFormat7MinY;
00174         int m_nFormat7Width;
00175         int m_nFormat7Height;
00176         
00177         // static for all instances
00178         // lib dc + raw specific camera data
00179         static raw1394handle_t m_handles[MAX_CAMERAS];
00180         static dc1394_cameracapture m_cameras[MAX_CAMERAS];
00181         static nodeid_t *m_pCameraNodes[MAX_PORTS];
00182 
00183         // internal camera data
00184         static int m_nOverallCameras;
00185         static TCameraInfo m_CameraInfo[MAX_CAMERAS];
00186         static CLinux1394Capture *m_pCameraOpener[MAX_CAMERAS];
00187 
00188         // static instance counter for handle destruction
00189         static int m_nInstances;
00190 };
00191 
00192 
00193 
00194 #endif /* _LINUX_1394_CAPTURE_H_ */


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