Linux1394Capture.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:  Linux1394Capture.cpp
00037 // Author:    Pedram Azad, Kai Welke
00038 // Date:      2005
00039 // ****************************************************************************
00040 // Changes:   24.08.2006. Kai Welke
00041 //            * Added YUV411 support
00042 //            26.09.2006, Kai Welke
00043 //            * added support for UIDs and different frame rates
00044 //            * open multiple captures to allow different rates and formats
00045 // ****************************************************************************
00046 
00047 
00048 // ****************************************************************************
00049 // Includes
00050 // ****************************************************************************
00051 
00052 #include "Linux1394Capture.h"
00053 #include "Image/ByteImage.h"
00054 #include "Image/ImageProcessor.h"
00055 
00056 #include <stdio.h>
00057 #include <stdlib.h>
00058 #include <stdarg.h>
00059 #include <algorithm>
00060 
00061 
00062 // ****************************************************************************
00063 // Defines
00064 // ****************************************************************************
00065 
00066 #define DROP_FRAMES 1
00067 #define NUM_BUFFERS 8
00068 
00069 
00070 // ****************************************************************************
00071 // Static members
00072 // ****************************************************************************
00073 
00074 int                     CLinux1394Capture::m_nOverallCameras = 0;
00075 CLinux1394Capture::TCameraInfo          CLinux1394Capture::m_CameraInfo[MAX_CAMERAS];
00076 CLinux1394Capture*      CLinux1394Capture::m_pCameraOpener[MAX_CAMERAS];
00077 int                     CLinux1394Capture::m_nInstances = 0;
00078 raw1394handle_t         CLinux1394Capture::m_handles[MAX_CAMERAS];
00079 dc1394_cameracapture    CLinux1394Capture::m_cameras[MAX_CAMERAS];
00080 nodeid_t*               CLinux1394Capture::m_pCameraNodes[MAX_PORTS];
00081 
00082 
00083 using namespace std;
00084 
00085 
00086 
00087 // ****************************************************************************
00088 // Constructors
00089 // ****************************************************************************
00090 
00091 CLinux1394Capture::CLinux1394Capture(int nCameras, VideoMode mode, ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType, FrameRate frameRate) : m_mode(mode), m_colorMode(colorMode), m_bayerPatternType(bayerPatternType), m_frameRate(frameRate)
00092 {
00093         m_nPorts = MAX_PORTS;
00094                 
00095         m_pTempImageHeader = new CByteImage();
00096         
00097         m_pTempImage = 0;
00098 
00099         m_nCameras = nCameras;
00100 
00101         width = -1;
00102         height = -1;
00103 
00104         m_bUseUIDs = false;
00105         m_bFormat7Mode = false;
00106 
00107         if(m_nInstances == 0)
00108         {
00109                 for(int i = 0 ; i < MAX_CAMERAS ; i++)
00110                 {
00111                         m_handles[i] = NULL;
00112                         m_pCameraOpener[i] = NULL;
00113                 }
00114         }
00115 
00116         m_nInstances++;
00117 }
00118 
00119 CLinux1394Capture::CLinux1394Capture(VideoMode mode, ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType, FrameRate frameRate, int nNumberUIDs, ...) : m_mode(mode), m_colorMode(colorMode), m_bayerPatternType(bayerPatternType), m_frameRate(frameRate)
00120 {
00121         // fill camera UIDS
00122         for(int i = 0 ; i < MAX_CAMERAS ; i++)
00123                 m_sCameraUID[i] = "";
00124 
00125         // read variable arguments
00126         va_list ap;
00127         va_start(ap, nNumberUIDs); 
00128 
00129         for(int u = 0 ; u < nNumberUIDs ; u++)
00130         {
00131                 const char* pch = va_arg(ap, const char*);
00132                 m_sCameraUID[u] += pch;
00133                 transform(m_sCameraUID[u].begin(), m_sCameraUID[u].end(), m_sCameraUID[u].begin(), (int(*)(int)) toupper);
00134         } 
00135 
00136         va_end(ap);
00137 
00138         m_nPorts = MAX_PORTS;
00139                 
00140         m_pTempImageHeader = new CByteImage();
00141         
00142         m_pTempImage = 0;
00143 
00144         m_nCameras = nNumberUIDs;
00145 
00146         width = -1;
00147         height = -1;
00148 
00149         m_bUseUIDs = true;
00150         m_bFormat7Mode = false;
00151 
00152         if(m_nInstances == 0)
00153         {
00154                 for(int i = 0 ; i < MAX_CAMERAS ; i++)
00155                 {
00156                         m_handles[i] = NULL;
00157                         m_pCameraOpener[i] = NULL;
00158                 }
00159         }
00160 
00161         m_nInstances++;
00162 }
00163 
00164 
00165 // ****************************************************************************
00166 // Constructors for Format7 Modes
00167 // ****************************************************************************
00168 
00169 CLinux1394Capture::CLinux1394Capture(int nCameras, VideoMode mode, int nFormat7PacketSize, int nFormat7MinX, int nFormat7MinY, int nFormat7Width, int nFormat7Height,
00170         ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType) :
00171         m_mode(mode), m_colorMode(colorMode), m_bayerPatternType(bayerPatternType)
00172 {
00173         m_nPorts = MAX_PORTS;
00174                 
00175         m_pTempImageHeader = new CByteImage();
00176         
00177         m_pTempImage = 0;
00178 
00179         m_nCameras = nCameras;
00180 
00181         width = -1;
00182         height = -1;
00183         
00184         m_bFormat7Mode = true;
00185         m_nFormat7PacketSize = nFormat7PacketSize == -1 ? USE_MAX_AVAIL : nFormat7PacketSize;
00186         m_nFormat7MinX = nFormat7MinX;
00187         m_nFormat7MinY = nFormat7MinY;
00188         m_nFormat7Width = nFormat7Width;
00189         m_nFormat7Height = nFormat7Height;
00190         
00191         m_bUseUIDs = false;
00192 
00193         if (m_nInstances == 0)
00194         {
00195                 for (int i = 0 ; i < MAX_CAMERAS ; i++)
00196                 {
00197                         m_handles[i] = NULL;
00198                         m_pCameraOpener[i] = NULL;
00199                 }
00200         }
00201 
00202         m_nInstances++;
00203 }
00204 
00205 CLinux1394Capture::CLinux1394Capture(VideoMode mode, int nFormat7PacketSize, int nFormat7MinX, int nFormat7MinY, int nFormat7Width, int nFormat7Height,
00206         ColorMode colorMode, ImageProcessor::BayerPatternType bayerPatternType, int nNumberUIDs, ...) :
00207         m_mode(mode), m_colorMode(colorMode), m_bayerPatternType(bayerPatternType)
00208 {
00209         // fill camera UIDS
00210         for(int i = 0 ; i < MAX_CAMERAS ; i++)
00211                 m_sCameraUID[i] = "";
00212 
00213         // read variable arguments
00214         va_list ap;
00215         va_start(ap, nNumberUIDs); 
00216 
00217         for(int u = 0 ; u < nNumberUIDs ; u++)
00218         {
00219                 const char* pch = va_arg(ap, const char*);
00220                 m_sCameraUID[u] += pch;
00221                 transform(m_sCameraUID[u].begin(), m_sCameraUID[u].end(), m_sCameraUID[u].begin(), (int(*)(int)) toupper);
00222         } 
00223 
00224         va_end(ap);
00225 
00226         m_nPorts = MAX_PORTS;
00227                 
00228         m_pTempImageHeader = new CByteImage();
00229         
00230         m_pTempImage = 0;
00231 
00232         m_nCameras = nNumberUIDs;
00233 
00234         width = -1;
00235         height = -1;
00236         
00237         m_bFormat7Mode = true;
00238         m_nFormat7PacketSize = nFormat7PacketSize == -1 ? USE_MAX_AVAIL : nFormat7PacketSize;
00239         m_nFormat7MinX = nFormat7MinX;
00240         m_nFormat7MinY = nFormat7MinY;
00241         m_nFormat7Width = nFormat7Width;
00242         m_nFormat7Height = nFormat7Height;
00243 
00244         m_bUseUIDs = true;
00245         m_bFormat7Mode = true;
00246 
00247         if (m_nInstances == 0)
00248         {
00249                 for (int i = 0 ; i < MAX_CAMERAS ; i++)
00250                 {
00251                         m_handles[i] = NULL;
00252                         m_pCameraOpener[i] = NULL;
00253                 }
00254         }
00255 
00256         m_nInstances++;
00257 }
00258 
00259 
00260 // ****************************************************************************
00261 // Destructor
00262 // ****************************************************************************
00263 
00264 CLinux1394Capture::~CLinux1394Capture()
00265 {
00266         CloseCamera();
00267         
00268         delete m_pTempImageHeader;
00269         
00270         if (m_pTempImage)
00271                 delete m_pTempImage;
00272 
00273         // clean up if last instance
00274         m_nInstances--;
00275 
00276         if(m_nInstances == 0)
00277         {
00278                 // release camera nodes
00279                 for(int p = 0 ; p < m_nPorts ; p++)
00280                         dc1394_free_camera_nodes(m_pCameraNodes[p]);
00281 
00282                 // destroy handles
00283                 for(int h = 0 ; h < m_nOverallCameras ; h++)
00284                         dc1394_destroy_handle(m_handles[h]);
00285 
00286                 m_nOverallCameras = 0;
00287         }
00288 }
00289 
00290 
00291 bool CLinux1394Capture::OpenCamera()
00292 {
00293         CloseCamera();
00294         
00295         // create temporary images and init modes
00296         if(!InitCameraMode())
00297         {
00298                 printf("error: selected camera mode not supported\n");
00299                 return false;
00300         }
00301 
00302         // retrieve info for all cameras
00303         if(!ListCameras())
00304         {
00305                 CloseCamera();
00306                 return false;
00307         }
00308         
00309         // open cameras
00310         if(m_bUseUIDs)
00311         {
00312                 for(int c = 0 ; c < m_nCameras ; c++)
00313                 {
00314                         bool bOpened = false;
00315                         for(int a = 0 ; a < m_nOverallCameras ; a++)
00316                         {
00317                                 if(m_sCameraUID[c] == m_CameraInfo[a].sUID)
00318                                 {
00319                                         if(m_pCameraOpener[a])
00320                                         {
00321                                                 printf("error: camera with UID 0x%s already opened\n", m_sCameraUID[c].c_str());
00322                                                 return false;
00323                                         }
00324                                         if(!OpenCamera(a))
00325                                                 return false;
00326 
00327                                         m_pCameraOpener[a] = this;
00328                                         m_nOpenedCameras[c] = a;
00329                                         bOpened = true;
00330                                 }
00331                         }
00332 
00333                         if(!bOpened)
00334                         {
00335                                 printf("error: could not find camera with UID 0x%s\n",m_sCameraUID[c].c_str());
00336                                 CloseCamera();
00337                                 return false;
00338                         }
00339                 }
00340         } else {
00341                 int nNumberCameras = 0;
00342                 for(int c = 0 ; c < m_nOverallCameras ; c++)
00343                 {
00344                         if(m_pCameraOpener[c] == NULL)
00345                         {
00346                                 if(!OpenCamera(c))
00347                                         return false;
00348         
00349                                 m_pCameraOpener[c] = this;
00350                                 m_nOpenedCameras[nNumberCameras] = c;
00351                                 nNumberCameras++;
00352                         }
00353 
00354                         if( (m_nCameras != -1) && (nNumberCameras == m_nCameras))
00355                                 break;
00356                 }
00357 
00358                 if(m_nCameras == -1) 
00359                 {
00360                         if(nNumberCameras == 0)
00361                         {
00362                                 printf("error: no camera found\n");
00363                                 CloseCamera();
00364                                 return false;
00365                         }
00366                         m_nCameras = nNumberCameras;
00367                 }
00368                 
00369                 if(nNumberCameras < m_nCameras)
00370                 {
00371                         printf("error: could not open requested number of cameras\n");
00372                         CloseCamera();
00373                         return false;
00374                 }
00375         }
00376 
00377         return true;
00378 }
00379 
00380 bool CLinux1394Capture::OpenCamera(int nCamera)
00381 {
00382         int p = m_CameraInfo[nCamera].nPort;
00383         int i = m_CameraInfo[nCamera].nIndex;
00384 
00385         printf("Opening camera %d: Port %d, Index %d, UID 0x%s, Format7 = %i\n",nCamera,p,i,m_CameraInfo[nCamera].sUID.c_str(), m_bFormat7Mode);
00386 
00387         char *device_name = 0;
00388         
00389         if (m_bFormat7Mode)
00390         {
00391                 if (dc1394_dma_setup_format7_capture(m_handles[nCamera], m_cameras[nCamera].node, i + 1, MODE_FORMAT7_0, SPEED_400, m_nFormat7PacketSize, m_nFormat7MinX, m_nFormat7MinY, m_nFormat7Width, m_nFormat7Height, NUM_BUFFERS, DROP_FRAMES, device_name, &m_cameras[nCamera]) != DC1394_SUCCESS)
00392                 {
00393                         printf("error: unable to setup camera (mode supported by camera?)\n");
00394                         CloseCamera();
00395                         return false;
00396                 }
00397         }
00398         else
00399                 {
00400                 if (dc1394_dma_setup_capture(m_handles[nCamera], m_cameras[nCamera].node, i + 1, FORMAT_VGA_NONCOMPRESSED, m_video_mode, SPEED_400, GetDCFrameRateMode(m_frameRate), NUM_BUFFERS, DROP_FRAMES, device_name, &m_cameras[nCamera]) != DC1394_SUCCESS)
00401                 {
00402                         printf("error: unable to setup camera (mode supported by camera?)\n");
00403                         CloseCamera();
00404                         return false;
00405                 }
00406         }
00407         
00408         // have the camera start sending us data
00409         if (dc1394_start_iso_transmission(m_handles[nCamera], m_cameras[nCamera].node) != DC1394_SUCCESS) 
00410         {
00411                 printf("error: unable to start camera iso transmission\n");
00412                 CloseCamera();
00413                 return false;
00414         }
00415 
00416         return true;
00417 }
00418 
00419 void CLinux1394Capture::CloseCamera()
00420 {
00421         for (int i = 0; i < m_nCameras; i++)
00422         {
00423                 if (m_handles[i])
00424                 {
00425                         if(m_pCameraOpener[i] == this)
00426                         {
00427                                 dc1394_dma_unlisten(m_handles[i], &m_cameras[i]);
00428                                 dc1394_dma_release_camera(m_handles[i], &m_cameras[i]);
00429                                 m_pCameraOpener[i] = NULL;
00430                         }
00431                 }
00432         }
00433         
00434         width = -1;
00435         height = -1;
00436         
00437         if (m_pTempImage)
00438         {
00439                 delete m_pTempImage;
00440                 m_pTempImage = 0;
00441         }
00442 }
00443 
00444 bool CLinux1394Capture::InitCameraMode()
00445 {
00446         width = -1;
00447         height = -1;
00448         int video_mode = 0;
00449 
00450         if (m_mode == e640x480)
00451         {
00452                 width = 640;
00453                 height = 480;
00454                         
00455                 m_pTempImageHeader->width = 640;
00456                 m_pTempImageHeader->height = 480;
00457                 
00458                 switch (m_colorMode)
00459                 {
00460                         case eGrayScale:
00461                         case eBayerPatternToRGB24:
00462                                 m_video_mode = MODE_640x480_MONO;
00463                         break;
00464                         
00465                         case eRGB24:
00466                                 m_video_mode = MODE_640x480_RGB;
00467                         break;
00468 
00469                         case eYUV411ToRGB24:
00470                                 m_video_mode = MODE_640x480_YUV411;
00471                         break;
00472                 }
00473         }
00474         else if (m_mode == e320x240)
00475         {
00476                 width = 320;
00477                 height = 240;
00478                 
00479                 switch (m_colorMode)
00480                 {
00481                         case eGrayScale:
00482                                 m_video_mode = MODE_640x480_MONO;
00483                                 m_pTempImageHeader->width = 640;
00484                                 m_pTempImageHeader->height = 480;
00485                         break;
00486                         
00487                         case eBayerPatternToRGB24:
00488                                 m_video_mode = MODE_640x480_MONO;
00489                                 m_pTempImage = new CByteImage(640, 480, CByteImage::eRGB24);
00490                                 m_pTempImageHeader->width = 640;
00491                                 m_pTempImageHeader->height = 480;
00492                         break;
00493                         
00494                         case eRGB24:
00495                                 m_video_mode = MODE_640x480_RGB;
00496                                 m_pTempImageHeader->width = 640;
00497                                 m_pTempImageHeader->height = 480;
00498                         break;
00499 
00500                         case eYUV411ToRGB24:
00501                                 m_video_mode = MODE_640x480_YUV411;
00502                                 m_pTempImage = new CByteImage(640, 480, CByteImage::eRGB24);
00503                                 m_pTempImageHeader->width = 640;
00504                                 m_pTempImageHeader->height = 480;
00505                                 break;
00506                 }
00507         }
00508         else
00509         {
00510                 // mode not supported
00511                 return false;
00512         }
00513         
00514         if (m_colorMode == eBayerPatternToRGB24 || m_colorMode == eGrayScale)
00515         {
00516                 m_pTempImageHeader->bytesPerPixel = 1;
00517                 m_pTempImageHeader->type = CByteImage::eGrayScale;
00518         }
00519         else if (m_colorMode == eRGB24 || m_colorMode == eYUV411ToRGB24)
00520         {
00521                 m_pTempImageHeader->bytesPerPixel = 3;
00522                 m_pTempImageHeader->type = CByteImage::eRGB24;
00523         }
00524 
00525         return true;
00526 }
00527 
00528 void CLinux1394Capture::ConvertYUV411(CByteImage* pInput, CByteImage* pOutput)
00529 {
00530 
00531         int width = pInput->width;
00532         int height = pInput->height;
00533 
00534         int y1,y2,y3,y4,u,v;
00535         int r,g,b;
00536         
00537         unsigned char* output = pOutput->pixels;
00538         unsigned char* input = pInput->pixels;
00539         // read chunks
00540         for(int i = 0 ; i < height ; i++)
00541         {
00542                 for(int j = 0 ; j < width / 4 ; j++)
00543                 {
00544                         u  = input[0];
00545                         y1 = input[1];
00546                         y2 = input[2];
00547 
00548                         v  = input[3];
00549                         y3 = input[4];
00550                         y4 = input[5];
00551                         
00552                         YUVToRGB(y1,u,v,output);
00553                         YUVToRGB(y2,u,v,output + 3);
00554                         YUVToRGB(y3,u,v,output + 6);
00555                         YUVToRGB(y4,u,v,output + 9);
00556                         
00557                         input += 6;
00558                         output += 12;
00559                 }
00560         }
00561 }
00562 
00563 void CLinux1394Capture::YUVToRGB(int y, int u, int v, unsigned char* output)
00564 {
00565         int r,g,b;
00566         
00567         // u and v are +-0.5
00568         u -= 128;
00569         v -= 128;
00570         
00571         // conversion
00572         r = int(y + 1.370705 * v);
00573         g = int(y - 0.698001 * v - 0.337633 * u);
00574         b = int(y + 1.732446 * u);
00575         
00576         // clamp to 0..1
00577         if (r < 0) r = 0;
00578         if (g < 0) g = 0;
00579         if (b < 0) b = 0;
00580         if (r > 255) r = 255;
00581         if (g > 255) g = 255;
00582         if (b > 255) b = 255;
00583         
00584         output[0] = (unsigned char) r;
00585         output[1] = (unsigned char) g;
00586         output[2] = (unsigned char) b;
00587 }
00588 
00589 bool CLinux1394Capture::CaptureImage(CByteImage **ppImages)
00590 {
00591         if ( (width == -1) || (height == -1) )
00592                 return false;
00593 
00594         int i;
00595 
00596         // first tell dc1394 that buffers can be reused
00597         for (i = 0; i < m_nCameras; i++)
00598         {
00599                 if (!m_handles[m_nOpenedCameras[i]])
00600                         return false;
00601                 
00602                 dc1394_dma_done_with_buffer(&m_cameras[m_nOpenedCameras[i]]);
00603         }
00604 
00605         for (i = 0; i < m_nCameras; i++)
00606         {
00607                 dc1394_dma_single_capture(&m_cameras[m_nOpenedCameras[i]]);
00608         }
00609 
00610         for (i = 0; i < m_nCameras; i++)
00611         {
00612                 m_pTempImageHeader->pixels = (unsigned char *) m_cameras[m_nOpenedCameras[i]].capture_buffer;
00613                 
00614                 if (m_mode == e640x480)
00615                 {
00616                         switch (m_colorMode)
00617                         {
00618                                 case eBayerPatternToRGB24:
00619                                         ImageProcessor::ConvertBayerPattern(m_pTempImageHeader, ppImages[i], m_bayerPatternType);
00620                                 break;
00621                                 
00622                                 case eGrayScale:
00623                                 case eRGB24:
00624                                         ImageProcessor::CopyImage(m_pTempImageHeader, ppImages[i]);
00625                                 break;
00626                                 case eYUV411ToRGB24:
00627                                         ConvertYUV411(m_pTempImageHeader, ppImages[i]);
00628                                 break;
00629                         }
00630                 }
00631                 else if (m_mode == e320x240)
00632                 {
00633                         switch (m_colorMode)
00634                         {
00635                                 case eBayerPatternToRGB24:
00636                                         ImageProcessor::ConvertBayerPattern(m_pTempImageHeader, m_pTempImage, m_bayerPatternType);
00637                                         ImageProcessor::Resize(m_pTempImage, ppImages[i]);
00638                                 break;
00639                                 
00640                                 case eGrayScale:
00641                                 case eRGB24:
00642                                         ImageProcessor::Resize(m_pTempImageHeader, ppImages[i]);
00643                                 break;
00644                                 case eYUV411ToRGB24:
00645                                         ConvertYUV411(m_pTempImageHeader, m_pTempImage);
00646                                         ImageProcessor::Resize(m_pTempImage, ppImages[i]);
00647                                 break;
00648                         }
00649                 }
00650         }
00651         
00652         return true;
00653 }
00654 
00655 bool CLinux1394Capture::CaptureBayerPatternImage(CByteImage **ppImages)
00656 {
00657         if ( (width == -1) || (height == -1) )
00658                 return false;
00659 
00660         int i;
00661 
00662         // first tell dc1394 that buffers can be reused
00663         for (i = 0; i < m_nCameras; i++)
00664         {
00665                 if (!m_handles[m_nOpenedCameras[i]])
00666                         return false;
00667                 
00668                 dc1394_dma_done_with_buffer(&m_cameras[m_nOpenedCameras[i]]);
00669         }
00670 
00671         for (i = 0; i < m_nCameras; i++)
00672         {
00673                 dc1394_dma_single_capture(&m_cameras[m_nOpenedCameras[i]]);
00674         }
00675 
00676         for (i = 0; i < m_nCameras; i++)
00677         {
00678                 m_pTempImageHeader->pixels = (unsigned char *) m_cameras[m_nOpenedCameras[i]].capture_buffer;
00679                 
00680                 if (m_mode == e640x480)
00681                 {
00682                         ImageProcessor::CopyImage(m_pTempImageHeader, ppImages[i]);
00683                 }
00684                 else if (m_mode == e320x240)
00685                 {
00686                         ImageProcessor::Resize(m_pTempImageHeader, ppImages[i]);
00687                 }
00688         }
00689         
00690         return true;
00691 }
00692 
00693 CByteImage::ImageType CLinux1394Capture::GetType()
00694 {
00695         switch (m_colorMode)
00696         {
00697                 case eYUV411ToRGB24:
00698                 case eBayerPatternToRGB24:
00699                 case eRGB24:
00700                         return CByteImage::eRGB24;
00701                 break;
00702                 
00703                 case eGrayScale:
00704                         return CByteImage::eGrayScale;
00705                 break;
00706         }
00707         
00708         return (CByteImage::ImageType) -1;
00709 }
00710 
00711 void CLinux1394Capture::SetGain(unsigned int nValue)
00712 {
00713         for (int i = 0; i < m_nCameras; i++)
00714         {
00715                 if (nValue == -1)
00716                 {
00717                         dc1394_auto_on_off(m_handles[i], m_cameras[i].node, FEATURE_GAIN, 1);
00718                 }
00719                 else
00720                 {
00721                         dc1394_auto_on_off(m_handles[i], m_cameras[i].node, FEATURE_GAIN, 0);
00722                         dc1394_set_gain(m_handles[i], m_cameras[i].node, nValue);
00723                 }
00724         }
00725 }
00726 
00727 void CLinux1394Capture::SetExposure(unsigned int nValue)
00728 {
00729         for (int i = 0; i < m_nCameras; i++)
00730         {
00731                 if (nValue == -1)
00732                 {
00733                         dc1394_auto_on_off(m_handles[i], m_cameras[i].node, FEATURE_EXPOSURE, 1);
00734                 }
00735                 else
00736                 {
00737                         dc1394_auto_on_off(m_handles[i], m_cameras[i].node, FEATURE_EXPOSURE, 0);
00738                         dc1394_set_exposure(m_handles[i], m_cameras[i].node, nValue);
00739                 }
00740         }
00741 }
00742 
00743 void CLinux1394Capture::SetShutter(unsigned int nValue)
00744 {
00745         for (int i = 0; i < m_nCameras; i++)
00746         {
00747                 if (nValue == -1)
00748                 {
00749                         dc1394_auto_on_off(m_handles[i], m_cameras[i].node, FEATURE_SHUTTER, 1);
00750                 }
00751                 else
00752                 {
00753                         dc1394_auto_on_off(m_handles[i], m_cameras[i].node, FEATURE_SHUTTER, 0);
00754                         dc1394_set_shutter(m_handles[i], m_cameras[i].node, nValue);
00755                 }
00756         }
00757 }
00758 
00759 int CLinux1394Capture::GetDCFrameRateMode(FrameRate frameRate)
00760 {
00761         switch(frameRate)
00762         {
00763                 case e60fps: return FRAMERATE_60;
00764                 case e30fps: return FRAMERATE_30;
00765                 case e15fps: return FRAMERATE_15;
00766                 case e7_5fps: return FRAMERATE_7_5;
00767                 case e3_75fps: return FRAMERATE_3_75;
00768                 case e1_875fps: return FRAMERATE_1_875;
00769 
00770                 default: return FRAMERATE_30;
00771         };
00772 }
00773 
00774 bool CLinux1394Capture::ListCameras()
00775 {
00776         // already listed
00777         if(m_nOverallCameras != 0)
00778                 return true;
00779 
00780         // first: count cameras
00781         raw1394handle_t raw_handle = raw1394_new_handle();
00782         if (!raw_handle)
00783         {
00784                 printf("error: unable to aquire a raw1394 handle\n");
00785                 return false;
00786         }
00787         
00788         raw1394_portinfo ports[MAX_PORTS];
00789         m_nPorts = raw1394_get_port_info(raw_handle, ports, m_nPorts);
00790         raw1394_destroy_handle(raw_handle);
00791         printf("number of ports = %d\n", m_nPorts);
00792 
00793         // build info for all cameras
00794         for (int p = 0; p < m_nPorts; p++)
00795         {
00796                 int camCount;
00797                 
00798                 // get the camera nodes and describe them as we find them
00799                 raw_handle = raw1394_new_handle();
00800                 raw1394_set_port(raw_handle, p);
00801                 m_pCameraNodes[p] = dc1394_get_camera_nodes(raw_handle, &camCount, 1);
00802                 raw1394_destroy_handle(raw_handle);
00803                 
00804                 // check cameras and retrieve info for capture
00805                 for (int i = 0; i < camCount; i++)
00806                 {
00807                         m_handles[m_nOverallCameras] = dc1394_create_handle(p);
00808                         if (!m_handles[m_nOverallCameras])
00809                         {
00810                                 printf("error: unable to aquire a raw1394 handle\n");
00811                                 CloseCamera();
00812                                 return false;
00813                         }
00814 
00815                         m_cameras[m_nOverallCameras].node = m_pCameraNodes[p][i];
00816                         dc1394_feature_set features;
00817         
00818                         if (dc1394_get_camera_feature_set(m_handles[m_nOverallCameras], m_cameras[m_nOverallCameras].node, &features) != DC1394_SUCCESS) 
00819                         {
00820                                 printf("info: unable to get feature set\n");
00821                         }
00822                         else
00823                         {
00824                                 //dc1394_print_feature_set(&m_features);
00825                         }
00826                         
00827                         unsigned int channel, speed;
00828                 
00829                         if (dc1394_get_iso_channel_and_speed(m_handles[m_nOverallCameras], m_cameras[m_nOverallCameras].node, &channel, &speed) != DC1394_SUCCESS) 
00830                         {
00831                                 printf("error: unable to get the iso channel number\n");
00832                                 CloseCamera();
00833                                 return false;
00834                         }
00835 
00836                         // retrieve camera info
00837                         dc1394_camerainfo info;
00838 
00839                         if (dc1394_get_camera_info(m_handles[m_nOverallCameras], m_cameras[m_nOverallCameras].node, &info) != DC1394_SUCCESS) 
00840                         {
00841                                 printf("error: unable to retrieve camera info\n");
00842                                 CloseCamera();  
00843                                 return false;           
00844                         } else {
00845                                 m_CameraInfo[m_nOverallCameras].nPort = p;
00846                                 m_CameraInfo[m_nOverallCameras].nIndex = i;
00847                                 unsigned int low = info.euid_64;
00848                                 unsigned int high = (info.euid_64 >> 32);
00849                                 m_CameraInfo[m_nOverallCameras].sUID = CamUIDToString(low,high);
00850                                 m_nOverallCameras++;
00851 
00852                                 if(m_nOverallCameras > MAX_CAMERAS)
00853                                 {
00854                                         printf("error: found more cameras than MAX_CAMERAS\n");
00855                                         CloseCamera();
00856                                         return false;
00857                                 }
00858                         }
00859                 }
00860         }
00861 
00862         return true;
00863 }
00864 
00865 std::string CLinux1394Capture::CamUIDToString(unsigned int nLow, unsigned int nHigh)
00866 {
00867         std::string UID = "";
00868         char szUID[17];
00869         sprintf(szUID,"%08X%08X\0",nHigh,nLow);
00870         UID += szUID;
00871         
00872         return UID;
00873 }


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