Linux1394Capture2.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:  Linux1394Capture2.h
00037 // Author:    Kai Welke, Pedram Azad
00038 // Date:      2007
00039 // ****************************************************************************
00040 // Requires:  * libdc1394v2
00041 //            * libraw1394 >= 1.2.0
00042 // ****************************************************************************
00043 // Changes:   20.12.2007. Kai Welke
00044 //            * Built CLinux1394Capture2 on base of CLinux1394Capture
00045 //            * switched from libdc1394v1 to libdc1394v2 (solved problem 
00046 //              with QT and allowed to use full firewire bandwidth)
00047 //            * added check for maximum bandwidth
00048 //            * generic camera feature access
00049 //            * Format7_0 implemented with ROI and framerate settings
00050 //              format7 support is camera dependant (dragonfly only
00051 //              supports two discrete framerates, dragonfly2 can be
00052 //              adjusted from 0.x ... 60.0 frames.
00053 // ****************************************************************************
00054 
00055 
00056 #ifndef _LINUX_1394_CAPTURE_2_H_
00057 #define _LINUX_1394_CAPTURE_2_H_
00058 
00059 
00060 // ****************************************************************************
00061 // Necessary includes
00062 // ****************************************************************************
00063 
00064 #include "Interfaces/VideoCaptureInterface.h"
00065 #include "Image/ImageProcessor.h"
00066 #include <string>
00067 #include <vector>
00068 
00069 #include <libraw1394/raw1394.h>
00070 #include <dc1394/dc1394.h>
00071 
00072 
00073 // ****************************************************************************
00074 // Forward declarations
00075 // ****************************************************************************
00076 
00077 class CByteImage;
00078 
00079 
00080 // ****************************************************************************
00081 // Defines
00082 // ****************************************************************************
00083 
00084 // don't set this smaller than 2
00085 #define MAX_CAMERAS 4 
00086 // maximum bandwidth of firewire (in quadlets / cycle)
00087 #define MAX_S400_BANDWIDTH 4915
00088 
00089 
00090 
00091 // ****************************************************************************
00092 // CLinux1394Capture2
00093 // ****************************************************************************
00094 
00095 class CLinux1394Capture2 : public CVideoCaptureInterface
00096 {
00097 public:
00098         // constructor, variable arguments are camera uids as const char*
00099         CLinux1394Capture2(int nCameras, VideoMode mode, ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType = ImageProcessor::eBayerRG, FrameRate frameRate = e30fps); 
00100         CLinux1394Capture2(VideoMode mode, ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType = ImageProcessor::eBayerRG, FrameRate frameRate = e30fps, int nNumberUIDs = 0, ...);
00101         
00102         // format 7 modes
00103         CLinux1394Capture2(int nCameras, VideoMode mode, float fFormat7FrameRate = 30.0f, int nFormat7MinX = 0, int nFormat7MinY = 0, int nFormat7Width = -1, int nFormat7Height = -1, ColorMode colorMode = CVideoCaptureInterface::eBayerPatternToRGB24, ImageProcessor::BayerPatternType bayerPatternType = ImageProcessor::eBayerRG);
00104         
00105         CLinux1394Capture2(VideoMode mode, float fFormat7FrameRate = 30.0f, int nFormat7MinX = 0, int nFormat7MinY = 0, int nFormat7Width = -1, int nFormat7Height = -1, ColorMode colorMode = CVideoCaptureInterface::eBayerPatternToRGB24, ImageProcessor::BayerPatternType bayerPatternType = ImageProcessor::eBayerRG, int nNumberUIDs = 0, ...);
00106         
00107         
00108         // destructor
00109         ~CLinux1394Capture2();
00110 
00111 
00112         // public methods
00113         bool OpenCamera();
00114         void CloseCamera();
00115         bool CaptureImage(CByteImage **ppImages);
00116         bool CaptureBayerPatternImage(CByteImage **ppImages);
00117         
00118     // SetCameraUids can be used if the UIDs are determined dynamically
00119         void SetCameraUids(std::vector<std::string> uids);   
00120         void SetGain(int nValue);
00121         void SetExposure(int nValue);
00122         void SetShutter(int nValue);
00123         void SetWhiteBalance(int nU, int nV, int nCamera = -1);
00124         void SetTemperature(int nTemperature);
00125         void SetFeature(dc1394feature_t feature, std::string sName, int nValue);
00126 
00127         void ListFeatures();
00128         
00129         int GetWidth() { return width; }
00130         int GetHeight() { return height; }
00131         CByteImage::ImageType GetType();
00132         int GetNumberOfCameras() { return m_nCameras; }
00133         
00134         dc1394camera_t* GetCameraHandle(int Index) { return m_cameras[Index]; }
00135 
00136         VideoMode GetVideoMode() const {return m_mode;}
00137         FrameRate GetFrameRate() const {return m_frameRate;}
00138 
00139 protected:
00140         // private methods
00141         void InitFirstInstance();
00142         void ExitLastInstance();
00143         void ResetAllCameras();
00144         
00145         bool OpenCamera(int nCamera);
00146         bool InitCameraMode();
00147         dc1394framerate_t GetDCFrameRateMode(FrameRate frameRate);
00148 
00149         // conversion
00150         void ConvertYUV411(CByteImage* pInput, CByteImage* pOutput);
00151         void YUVToRGB(int y, int u, int v, unsigned char* output);
00152 
00153         // multiple camera handling
00154         bool ListCameras();
00155         std::string CamUIDToString(uint64_t uid);
00156         
00157         // private attributes
00158         // temporary images for capruting
00159         CByteImage *m_pTempImageHeader;
00160         
00161         int m_nMode;
00162 
00163         int width;
00164         int height;
00165         
00166         // number of cameras requested by user
00167         int m_nCameras;
00168         // requested video mode (see VideoCaptureInterface.h)
00169         const VideoMode m_mode;
00170         // requested color mode (see VideoCaptureInterface.h)
00171         const ColorMode m_colorMode;
00172         // requested frame rate (see VideoCaptureInterface.h)
00173         FrameRate m_frameRate;
00174         // requested bayer pattern type (see ImageProcessor.h)
00175         const ImageProcessor::BayerPatternType m_bayerPatternType;
00176         // unique camera ids as requested by user
00177         std::string m_sCameraUID[MAX_CAMERAS];
00178         bool m_bUseUIDs;
00179         // opened camera ids
00180         int m_nOpenedCameras[MAX_CAMERAS];
00181         // video mode
00182         dc1394video_mode_t m_video_mode;
00183         // format 7 mode
00184         bool m_bFormat7Mode;
00185         float m_fFormat7FrameRate;
00186         int m_nFormat7MinX;
00187         int m_nFormat7MinY;
00188         int m_nFormat7Width;
00189         int m_nFormat7Height;
00190         
00191         // static for all instances
00192         // lib dc + raw specific camera data
00193         static dc1394_t*       m_pDC1394;
00194         static dc1394camera_t* m_cameras[MAX_CAMERAS];
00195 
00196         // internal camera data
00197         static int m_nOverallCameras;
00198         static int m_nRemainingBandwidth;
00199         static CLinux1394Capture2 *m_pCameraOpener[MAX_CAMERAS];
00200         static int m_nCameraBandwidth[MAX_CAMERAS];
00201 
00202         // static instance counter for handle destruction
00203         static int m_nInstances;
00204 };
00205 
00206 
00207 
00208 #endif /* _LINUX_1394_CAPTURE_2_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