Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes
CLinux1394Capture2 Class Reference

#include <Linux1394Capture2.h>

Inheritance diagram for CLinux1394Capture2:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool CaptureBayerPatternImage (CByteImage **ppImages)
bool CaptureImage (CByteImage **ppImages)
 CLinux1394Capture2 (int nCameras, VideoMode mode, ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType=ImageProcessor::eBayerRG, FrameRate frameRate=e30fps)
 CLinux1394Capture2 (VideoMode mode, ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType=ImageProcessor::eBayerRG, FrameRate frameRate=e30fps, int nNumberUIDs=0,...)
 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)
 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,...)
void CloseCamera ()
dc1394camera_t * GetCameraHandle (int Index)
FrameRate GetFrameRate () const
int GetHeight ()
int GetNumberOfCameras ()
CByteImage::ImageType GetType ()
VideoMode GetVideoMode () const
int GetWidth ()
void ListFeatures ()
bool OpenCamera ()
void SetCameraUids (std::vector< std::string > uids)
void SetExposure (int nValue)
void SetFeature (dc1394feature_t feature, std::string sName, int nValue)
void SetGain (int nValue)
void SetShutter (int nValue)
void SetTemperature (int nTemperature)
void SetWhiteBalance (int nU, int nV, int nCamera=-1)
 ~CLinux1394Capture2 ()

Protected Member Functions

std::string CamUIDToString (uint64_t uid)
void ConvertYUV411 (CByteImage *pInput, CByteImage *pOutput)
void ExitLastInstance ()
dc1394framerate_t GetDCFrameRateMode (FrameRate frameRate)
bool InitCameraMode ()
void InitFirstInstance ()
bool ListCameras ()
bool OpenCamera (int nCamera)
void ResetAllCameras ()
void YUVToRGB (int y, int u, int v, unsigned char *output)

Protected Attributes

int height
const
ImageProcessor::BayerPatternType 
m_bayerPatternType
bool m_bFormat7Mode
bool m_bUseUIDs
const ColorMode m_colorMode
float m_fFormat7FrameRate
FrameRate m_frameRate
const VideoMode m_mode
int m_nCameras
int m_nFormat7Height
int m_nFormat7MinX
int m_nFormat7MinY
int m_nFormat7Width
int m_nMode
int m_nOpenedCameras [MAX_CAMERAS]
CByteImagem_pTempImageHeader
std::string m_sCameraUID [MAX_CAMERAS]
dc1394video_mode_t m_video_mode
int width

Static Protected Attributes

static dc1394camera_t * m_cameras [MAX_CAMERAS]
static int m_nCameraBandwidth [MAX_CAMERAS]
static int m_nInstances = 0
static int m_nOverallCameras = 0
static int m_nRemainingBandwidth = MAX_S400_BANDWIDTH
static CLinux1394Capture2m_pCameraOpener [MAX_CAMERAS]
static dc1394_t * m_pDC1394

Detailed Description

Definition at line 95 of file Linux1394Capture2.h.


Constructor & Destructor Documentation

CLinux1394Capture2::CLinux1394Capture2 ( int  nCameras,
VideoMode  mode,
ColorMode  colorMode,
ImageProcessor::BayerPatternType  bayerPatternType = ImageProcessor::eBayerRG,
FrameRate  frameRate = e30fps 
)

Definition at line 102 of file Linux1394Capture2.cpp.

CLinux1394Capture2::CLinux1394Capture2 ( VideoMode  mode,
ColorMode  colorMode,
ImageProcessor::BayerPatternType  bayerPatternType = ImageProcessor::eBayerRG,
FrameRate  frameRate = e30fps,
int  nNumberUIDs = 0,
  ... 
)

Definition at line 125 of file Linux1394Capture2.cpp.

CLinux1394Capture2::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 
)

Definition at line 170 of file Linux1394Capture2.cpp.

CLinux1394Capture2::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,
  ... 
)

Definition at line 216 of file Linux1394Capture2.cpp.

Definition at line 286 of file Linux1394Capture2.cpp.


Member Function Documentation

std::string CLinux1394Capture2::CamUIDToString ( uint64_t  uid) [protected]

Definition at line 1145 of file Linux1394Capture2.cpp.

Definition at line 848 of file Linux1394Capture2.cpp.

bool CLinux1394Capture2::CaptureImage ( CByteImage **  ppImages) [virtual]

Implements CVideoCaptureInterface.

Definition at line 799 of file Linux1394Capture2.cpp.

Implements CVideoCaptureInterface.

Definition at line 561 of file Linux1394Capture2.cpp.

void CLinux1394Capture2::ConvertYUV411 ( CByteImage pInput,
CByteImage pOutput 
) [protected]

Definition at line 734 of file Linux1394Capture2.cpp.

Definition at line 325 of file Linux1394Capture2.cpp.

dc1394camera_t* CLinux1394Capture2::GetCameraHandle ( int  Index) [inline]

Definition at line 134 of file Linux1394Capture2.h.

dc1394framerate_t CLinux1394Capture2::GetDCFrameRateMode ( FrameRate  frameRate) [protected]

Definition at line 1039 of file Linux1394Capture2.cpp.

Definition at line 137 of file Linux1394Capture2.h.

int CLinux1394Capture2::GetHeight ( ) [inline, virtual]

Implements CVideoCaptureInterface.

Definition at line 130 of file Linux1394Capture2.h.

int CLinux1394Capture2::GetNumberOfCameras ( ) [inline, virtual]

Implements CVideoCaptureInterface.

Definition at line 132 of file Linux1394Capture2.h.

Implements CVideoCaptureInterface.

Definition at line 897 of file Linux1394Capture2.cpp.

Definition at line 136 of file Linux1394Capture2.h.

int CLinux1394Capture2::GetWidth ( ) [inline, virtual]

Implements CVideoCaptureInterface.

Definition at line 129 of file Linux1394Capture2.h.

bool CLinux1394Capture2::InitCameraMode ( ) [protected]

Definition at line 587 of file Linux1394Capture2.cpp.

Definition at line 307 of file Linux1394Capture2.cpp.

bool CLinux1394Capture2::ListCameras ( ) [protected]

Definition at line 1092 of file Linux1394Capture2.cpp.

Definition at line 965 of file Linux1394Capture2.cpp.

bool CLinux1394Capture2::OpenCamera ( ) [virtual]

Implements CVideoCaptureInterface.

Definition at line 342 of file Linux1394Capture2.cpp.

bool CLinux1394Capture2::OpenCamera ( int  nCamera) [protected]

Definition at line 431 of file Linux1394Capture2.cpp.

Definition at line 1054 of file Linux1394Capture2.cpp.

Definition at line 915 of file Linux1394Capture2.cpp.

Definition at line 931 of file Linux1394Capture2.cpp.

void CLinux1394Capture2::SetFeature ( dc1394feature_t  feature,
std::string  sName,
int  nValue 
)

Definition at line 978 of file Linux1394Capture2.cpp.

Definition at line 926 of file Linux1394Capture2.cpp.

Definition at line 936 of file Linux1394Capture2.cpp.

Definition at line 956 of file Linux1394Capture2.cpp.

void CLinux1394Capture2::SetWhiteBalance ( int  nU,
int  nV,
int  nCamera = -1 
)

Definition at line 941 of file Linux1394Capture2.cpp.

void CLinux1394Capture2::YUVToRGB ( int  y,
int  u,
int  v,
unsigned char *  output 
) [protected]

Definition at line 768 of file Linux1394Capture2.cpp.


Member Data Documentation

int CLinux1394Capture2::height [protected]

Definition at line 164 of file Linux1394Capture2.h.

Definition at line 175 of file Linux1394Capture2.h.

Definition at line 184 of file Linux1394Capture2.h.

Definition at line 178 of file Linux1394Capture2.h.

dc1394camera_t * CLinux1394Capture2::m_cameras [static, protected]

Definition at line 194 of file Linux1394Capture2.h.

Definition at line 171 of file Linux1394Capture2.h.

Definition at line 185 of file Linux1394Capture2.h.

Definition at line 173 of file Linux1394Capture2.h.

Definition at line 169 of file Linux1394Capture2.h.

int CLinux1394Capture2::m_nCameraBandwidth [static, protected]

Definition at line 200 of file Linux1394Capture2.h.

Definition at line 167 of file Linux1394Capture2.h.

Definition at line 189 of file Linux1394Capture2.h.

Definition at line 186 of file Linux1394Capture2.h.

Definition at line 187 of file Linux1394Capture2.h.

Definition at line 188 of file Linux1394Capture2.h.

int CLinux1394Capture2::m_nInstances = 0 [static, protected]

Definition at line 203 of file Linux1394Capture2.h.

int CLinux1394Capture2::m_nMode [protected]

Definition at line 161 of file Linux1394Capture2.h.

Definition at line 180 of file Linux1394Capture2.h.

int CLinux1394Capture2::m_nOverallCameras = 0 [static, protected]

Definition at line 197 of file Linux1394Capture2.h.

Definition at line 198 of file Linux1394Capture2.h.

Definition at line 199 of file Linux1394Capture2.h.

dc1394_t * CLinux1394Capture2::m_pDC1394 [static, protected]

Definition at line 193 of file Linux1394Capture2.h.

Definition at line 159 of file Linux1394Capture2.h.

Definition at line 177 of file Linux1394Capture2.h.

dc1394video_mode_t CLinux1394Capture2::m_video_mode [protected]

Definition at line 182 of file Linux1394Capture2.h.

int CLinux1394Capture2::width [protected]

Definition at line 163 of file Linux1394Capture2.h.


The documentation for this class was generated from the following files:


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:58