GrabbingDevice.cpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002 *  GrabbingDevice.cpp
00003 *
00004 *  (C) 2009 AG Aktives Sehen <agas@uni-koblenz.de>
00005 *           Universitaet Koblenz-Landau
00006 ******************************************************************************/
00007 
00008 
00009 #include "GrabbingDevice.h"
00010 
00011 //#include "Architecture/Serializer/ImageCompressor.h"
00012 
00013 // PUMA LIBS
00014 #include "../../Workers/Puma2/ColorImageRGB8.h"
00015 #include "../../Workers/Puma2/PumaException.h"
00016 
00017 // STL
00018 #include <algorithm>
00019 #include <iostream>
00020 #include <fstream>
00021 #include <sstream>
00022 
00023 #include <cstring>
00024 #include <string>
00025 
00026 #include <stdio.h>
00027 
00028 using namespace puma2;
00029 using namespace std;
00030 
00031 //#define DEBUG
00032 
00033 #define MAX_NUM_BUFFERS 64
00034 
00035 
00036 GrabbingDevice::GrabbingDevice ( unicap_handle_t _handle )
00037 {
00038   m_Handle = _handle;
00039   unicap_get_device ( m_Handle, &m_Device );
00040 
00041   m_TargetFourCC  = UCIL_FOURCC ( 'R', 'G', 'B', '3' );
00042   m_NumBuffers = 4;
00043 
00044   detectFormats();
00045   detectProperties();
00046 
00047 #ifdef DEBUG
00048   printf ( "%s Line[%d] : creating new device with handle: %li \n",
00049            __FILE__, __LINE__, ( long int ) m_Handle );
00050 #endif
00051 }
00052 
00053 
00054 
00055 GrabbingDevice::~GrabbingDevice()
00056 {
00057 //  TRACE_SYSTEMINFO( "Stopping Capture process.." )
00058 //  unicap_stop_capture ( m_Handle );
00059 //  TRACE_SYSTEMINFO( "Closing device.." )
00060 //  unicap_close ( m_Handle );
00061 
00062 //  TRACE_SYSTEMINFO( "Deleting buffers.." )
00064 //  for ( uint i = 0; i < m_Buffers.size(); i++ )
00065 //  {
00066 //    free ( m_Buffers.at ( i )->data );
00067 //    delete m_Buffers.at ( i );
00068 //  }
00069 
00070 //  TRACE_SYSTEMINFO( "Freeing formats memory.." )
00071 //  for ( unsigned int i = 0; i < m_Formats.size(); i++ )
00072 //  {
00073 //    delete m_Formats[i];
00074 //  }
00075 
00076 //  TRACE_SYSTEMINFO( "Freeing properties memory.." )
00077 //  for ( unsigned int i = 0; i < m_Properties.size(); i++ )
00078 //  {
00079 //    delete m_Properties[i];
00080 //  }
00081 
00082 }
00083 
00084 
00085 bool GrabbingDevice::setFormat ( const uint _formatId, const uint _subformatId )
00086 {
00087   bool result = false;
00088 
00089 //  TRACE_INFO( "Setting format " + Tracer::toString( _formatId ) + "." + Tracer::toString( _subformatId ) );
00090 
00091 //  // check if some parameters are out of range
00092 //  if ( _formatId > m_Formats.size() ) {
00093 //    TRACE_ERROR( "Invalid format ID" );
00094 //    return false;
00095 //  }
00096 //  if ( ( int ) _subformatId > m_Formats.at ( _formatId )->size_count )
00097 //  {
00098 //    TRACE_ERROR( "Invalid subformat ID" );
00099 //    return false;
00100 //  }
00101 
00102   // if selected format provides multiple resolutions
00103   if ( m_Formats[_formatId]->size_count != 0 )
00104   {
00105     m_Formats[_formatId]->size.width = m_Formats[_formatId]->sizes[_subformatId].width;
00106     m_Formats[_formatId]->size.height = m_Formats[_formatId]->sizes[_subformatId].height;
00107   }
00108   result = setFormat ( m_Formats[_formatId] );
00109   return result;
00110 }
00111 
00112 
00113 bool GrabbingDevice::setFormat ( int width, int height, std::string fourcc )
00114 {
00115   if ( fourcc.size() != 4 )
00116   {
00117     string str( "Invalid fourcc" );
00118     throw PumaException( PumaException::ignorable, str );
00119   }
00120   unsigned int ucil_fourcc = UCIL_FOURCC( fourcc[0], fourcc[1], fourcc[2], fourcc[3] );
00121 
00122   for ( uint formatId = 0; formatId < m_Formats.size(); formatId++)
00123   {
00124     if ( m_Formats.at(formatId)->size_count == 0 )
00125     {
00126       // there are no sub formats, check main format
00127       if ( ( m_Formats.at(formatId)->size.width == width ) &&
00128            ( m_Formats.at(formatId)->size.height == height ) &&
00129            ( m_Formats.at(formatId)->fourcc == ucil_fourcc ))
00130       {
00131         return setFormat( formatId, 0 );
00132       }
00133     }
00134     else
00135     {
00136       //look if there is a fitting sub format
00137       for ( int subFormatId = 0; subFormatId < m_Formats.at(formatId)->size_count; subFormatId++ )
00138       {
00139         if ( ( m_Formats.at(formatId)->sizes[ subFormatId ].width == width ) &&
00140                ( m_Formats.at(formatId)->sizes[ subFormatId ].height == height ) &&
00141                ( m_Formats.at(formatId)->fourcc == ucil_fourcc ) )
00142         {
00143           //select subformat size
00144           m_Formats[formatId]->size.width = m_Formats[formatId]->sizes[subFormatId].width;
00145           m_Formats[formatId]->size.height = m_Formats[formatId]->sizes[subFormatId].height;
00146           return setFormat( formatId, subFormatId );
00147         }
00148       }
00149     }
00150   }
00151 
00152   //TRACE_ERROR( "No format matching " + toString( width ) + "x" + toString( height ) + " / " + fourcc + " found!" );
00153   return false;
00154 }
00155 
00156 
00157 bool GrabbingDevice::setFormat ( unicap_format_t* _format )
00158 {
00159   bool result = true;
00160 
00161   _format->buffer_type = UNICAP_BUFFER_TYPE_USER;
00162 
00163 //  TRACE_INFO( "Setting format " + Tracer::toString( _format->size.width ) + "x" + Tracer::toString( _format->size.height ) );
00164 
00165 //  if ( SUCCESS ( unicap_set_format ( m_Handle, _format ) ) )
00166 //  {
00167 //    m_CurrentFormat = _format;
00168 //    if ( m_CurrentFormat->fourcc == UCIL_FOURCC('M','J','P','G') )
00169 //    {
00170 //      m_CurrentFormat->buffer_size = _format->size.width*_format->size.height*4+1024;
00171 //      TRACE_INFO( "MJPEG format selected. Setting buffer size to " + Tracer::toString( m_CurrentFormat->buffer_size ) + " bytes." );
00172 //    }
00173 //  }
00174 //  else
00175 //  {
00176 //    string message ( "Unable to set format!" );
00177 //    throw  PumaException ( PumaException::intolerable, message );
00178 //    result = false;
00179 //  }
00180 
00181   // buffer size may have changed
00182   prepareBuffers();
00183 
00184   // properties may have changed
00185   result &= detectProperties();
00186 
00187   return result;
00188 }
00189 
00190 
00191 string GrabbingDevice::getFormatDesc()
00192 {
00193   string result ( m_CurrentFormat->identifier );
00194   return result;
00195 }
00196 
00197 
00198 
00199 string GrabbingDevice::getFormatDesc ( const uint _formatId )
00200 {
00201   if ( _formatId >= m_Formats.size() )
00202   {
00203     string message ( "format index out of range" );
00204     throw  PumaException ( PumaException::ignorable, message );
00205     string result ( "unknown" );
00206     return result;
00207   }
00208 
00209   string result ( m_Formats.at ( _formatId )->identifier );
00210   return result;
00211 }
00212 
00213 
00214 
00215 uint GrabbingDevice::getFormatDepth()
00216 {
00217   if ( m_CurrentFormat == 0 ) return 0;
00218   return ( uint ) m_CurrentFormat->bpp;
00219 }
00220 
00221 
00222 uint GrabbingDevice::getFrameWidth()
00223 {
00224   if ( m_CurrentFormat == 0 ) return 0;
00225   return ( uint ) m_CurrentFormat->size.width;
00226 }
00227 
00228 uint GrabbingDevice::getFrameHeight()
00229 {
00230   if ( m_CurrentFormat == 0 ) return 0;
00231   return ( uint ) m_CurrentFormat->size.height;
00232 }
00233 
00234 uint GrabbingDevice::getFrameSize()
00235 {
00236   //if ( m_CurrentFormat == 0) return 0;
00237   return ( m_ConvertedBuffer.format.size.width *
00238            m_ConvertedBuffer.format.size.height *
00239            m_ConvertedBuffer.format.bpp / 8 );
00240 }
00241 
00242 bool GrabbingDevice::setNumBuffers ( uint _numBuffers )
00243 {
00244   if ( ( _numBuffers < 2 ) || ( _numBuffers > MAX_NUM_BUFFERS ) ) return false;
00245   m_NumBuffers = _numBuffers;
00246   if ( m_CurrentFormat )
00247   {
00248     return prepareBuffers();
00249   }
00250   else
00251   {
00252     return true;
00253   }
00254 }
00255 
00256 
00257 uint GrabbingDevice::getNumBuffers()
00258 {
00259   return m_NumBuffers;
00260 }
00261 
00262 
00263 bool GrabbingDevice::setProperty ( const string &_name, const string &_value )
00264 {
00265   property_value_t val;
00266   strcpy ( val.menuItem, _value.c_str() );
00267   return setProperty ( _name, val, false );
00268 }
00269 
00270 
00271 
00272 bool GrabbingDevice::setProperty ( const string &_name, double &_value, bool _normalized )
00273 {
00274   property_value_t val;
00275   val.value = _value;
00276   return setProperty ( _name, val, _normalized );
00277 }
00278 
00279 
00280 bool GrabbingDevice::setProperty ( unicap_property_t &_property )
00281 {
00282   if ( ! SUCCESS ( unicap_set_property ( m_Handle, &_property ) ) )
00283   {
00284     string message ( "unable to set property" );
00285     throw  PumaException ( PumaException::ignorable, message );
00286     return false;
00287   }
00288   return true;
00289 }
00290 
00291 
00292 
00293 bool GrabbingDevice::getProperty ( unicap_property_t **_property, uint _id )
00294 {
00295   return findPropertyById ( _property, _id );
00296 }
00297 
00298 
00299 
00300 bool GrabbingDevice::getProperty ( unicap_property_t **_property, string &_desc )
00301 {
00302   return findPropertyByDesc ( _property, _desc );
00303 }
00304 
00305 
00306 void GrabbingDevice::cleanBuffers()
00307 {
00308   int numBuffersReady = 0;
00309   unicap_data_buffer_t *capturedBuffer = 0;
00310 
00311   // get number of filled buffers
00312 //  if ( ! SUCCESS ( unicap_poll_buffer ( m_Handle, &numBuffersReady ) ) )
00313 //  {
00314 //    numBuffersReady = 1;
00315 //    TRACE_WARNING("Could not poll unicap buffer. Setting buffer count to 1.");
00316 //  }
00317 
00318   // free already filled and outdatet buffers
00319   for ( int i = 0; i < numBuffersReady; i++ )
00320   {
00321     unicap_wait_buffer ( m_Handle, &capturedBuffer );
00322     unicap_queue_buffer ( m_Handle, capturedBuffer );
00323   }
00324 }
00325 
00326 
00327 bool GrabbingDevice::setOutputColorspace ( string fourcc )
00328 {
00329   if ( fourcc.size() != 4 )
00330   {
00331     string str( "Invalid fourcc" );
00332     throw PumaException( PumaException::ignorable, str );
00333   }
00334   return setOutputColorspace( UCIL_FOURCC( fourcc[0], fourcc[1], fourcc[2], fourcc[3] ) );
00335 }
00336 
00337 bool GrabbingDevice::setOutputColorspace ( uint _fourcc )
00338 {
00339   int conversion_status = ucil_conversion_supported ( _fourcc,  m_CurrentFormat->fourcc );
00340 
00341   if ( conversion_status == 0 )
00342   {
00343     printf ( "%s Line[%d] : colorspace conversion from %s to %s NOT! supported \n",
00344              __FILE__,
00345              __LINE__,
00346              toString ( _fourcc ).c_str(), toString ( m_CurrentFormat->fourcc ).c_str() );
00347 
00348     string message ( "colorspace with fourcc" );
00349     message += toString ( _fourcc );
00350     message += " could not be selected";
00351     throw  PumaException ( PumaException::ignorable, message );
00352 
00353     return false;
00354   }
00355 
00356 #ifdef DEBUG
00357   printf ( "%s Line[%d] : colorspace conversion from %s to %s supported  \n",
00358            __FILE__, __LINE__,  toString ( _fourcc ).c_str(), toString ( m_CurrentFormat->fourcc ).c_str() );
00359 #endif
00360 
00361   // save fourcc code
00362   m_TargetFourCC = _fourcc;
00363 
00364   // copy format info
00365   unicap_copy_format ( &m_ConvertedBuffer.format, m_CurrentFormat );
00366 
00367   // apply changes
00368   m_ConvertedBuffer.format.fourcc = m_TargetFourCC;
00369 
00370   switch ( ucil_get_colorspace_from_fourcc ( m_TargetFourCC ) )
00371   {
00372     case UCIL_COLORSPACE_RGB24:
00373       m_ConvertedBuffer.format.bpp = 24;
00374       break;
00375 
00376     case UCIL_COLORSPACE_RGB32:
00377       m_ConvertedBuffer.format.bpp = 32;
00378       break;
00379 
00380     case UCIL_COLORSPACE_Y8:
00381       m_ConvertedBuffer.format.bpp = 8;
00382       break;
00383 
00384     case UCIL_COLORSPACE_YUV:
00385       m_ConvertedBuffer.format.bpp = 16;
00386       break;
00387 
00388     case UCIL_COLORSPACE_UNKNOWN:
00389       printf ( "Colorspace unknown!\n" );
00390       m_ConvertedBuffer.format.bpp = 32; // should be safe ..
00391   }
00392 
00393   return true;
00394 }
00395 
00396 
00397 bool GrabbingDevice::grabImage ( ColorImageRGB8 &_image )
00398 {
00399   unicap_data_buffer_t *capturedBuffer = 0;
00400   unicap_data_buffer_t destBuffer;
00401 
00402   cleanBuffers();
00403 
00404   // get current buffer
00405   unicap_status_t gotBuffer = unicap_wait_buffer ( m_Handle, &capturedBuffer );
00406 
00407   // if current buffer could not be fetched
00408   if ( !SUCCESS ( gotBuffer ) )
00409   {
00410     printf ( "failed to wait for buffer\n" );
00411     unicap_queue_buffer ( m_Handle, capturedBuffer );
00412     return false;
00413   }
00414 
00415   // adapt image to current format
00416   _image.resize ( m_CurrentFormat->size.width, m_CurrentFormat->size.height );
00417 
00418   if ( m_CurrentFormat->fourcc == UCIL_FOURCC('M','J','P','G') )
00419   {
00420     //convert MJPEG 'by hand'
00421 /*    if (capturedBuffer->frame_number == 0)
00422     {
00423       //always skip first frame because it contains invalid data (reason unknown)
00424       unicap_queue_buffer ( m_Handle, capturedBuffer );
00425       return true;
00426     }*/
00427 //    TRACE_SYSTEMINFO( "Decompressing MJPEG of size " + Tracer::toString( m_CurrentFormat->size.width ) + "x" + Tracer::toString( m_CurrentFormat->size.height ) );
00428 
00429 //    try {
00430 //      ImageCompressor::decompress( capturedBuffer->buffer_size, capturedBuffer->data, _image );
00431 //    }
00432 //    catch ( const char* msg ) {
00433 //      TRACE_ERROR( msg );
00434 //    }
00435 
00436     unicap_queue_buffer ( m_Handle, capturedBuffer );
00437   /*
00438     unsigned char tmp1[ capturedBuffer-> ];
00439     int bytesRead=copyBuffer(tmp1);
00440     Messages::ImageM* msg=new Messages::ImageM(srcId,camSrc.width,camSrc.height,tmp1,bytesRead);
00441     bool ret=Worker::MJPG::decompressJPG( tmp1,bytesRead,(unsigned char*)msg->getImage().getPixels());
00442     if (!ret)
00443     {
00444       return false;
00445     }
00446   */
00447   }
00448   else
00449   {
00450     //let UCIL convert the buffer
00451     ColorImageRGB8::PixelType **ptr = _image.unsafeRowPointerArray();
00452 
00453     memset ( &destBuffer, 0x0, sizeof ( unicap_data_buffer_t ) );
00454 
00455     // adapt destination buffer
00456     unicap_copy_format ( &destBuffer.format, m_CurrentFormat );
00457     destBuffer.format.fourcc = UCIL_FOURCC ( 'R', 'G', 'B', '3' );
00458     destBuffer.buffer_size = m_CurrentFormat->size.width *  m_CurrentFormat->size.height * 3;
00459     destBuffer.data = ( unsigned char* ) ptr[0];
00460 
00461     unicap_status_t converted = ucil_convert_buffer ( &destBuffer, capturedBuffer );
00462 
00463     // put buffer back to queue
00464     unicap_queue_buffer ( m_Handle, capturedBuffer );
00465 
00466     if ( !SUCCESS( converted ) )
00467     {
00468       printf ( "color conversion failed\n" );
00469       return false;
00470     }
00471   }
00472 
00473   return true;
00474 }
00475 
00476 
00477 
00478 bool GrabbingDevice::grabData ( unsigned char *_data, std::string fourcc )
00479 {
00480 /*
00481   if ( m_CurrentFormat->fourcc == UCIL_FOURCC('M','J','P','G') )
00482   {
00483     if ( fourcc != "UYVY" )
00484     {
00485       return false;
00486     }
00487     
00488     ColorImageRGB8 image;
00489     if ( !grabImage ( image ) )
00490     {
00491       return false;
00492     }
00493     unsigned char *rgbData = image.unsafeRowPointerArray()[0];
00494     return true;
00495   }
00496 */
00497   
00498   bool result = false;
00499   unicap_data_buffer_t *capturedBuffer = 0;
00500 
00501   cleanBuffers();
00502 
00503   unicap_status_t gotBuffer = unicap_wait_buffer ( m_Handle, &capturedBuffer );
00504 
00505   if ( !SUCCESS ( gotBuffer ) )
00506   {
00507     printf ( "failed to wait for buffer\n" );
00508     unicap_queue_buffer ( m_Handle, capturedBuffer );
00509     return result;
00510   }
00511 
00512   setOutputColorspace( fourcc );
00513 
00514   // set location for converted data
00515   m_ConvertedBuffer.data = _data;
00516 
00517   // conversion required, will be supported, otherwise it would not have been set
00518   unicap_status_t converted = ucil_convert_buffer ( &m_ConvertedBuffer, capturedBuffer );
00519 
00520   // put buffer back to queue
00521   unicap_queue_buffer ( m_Handle, capturedBuffer );
00522 
00523   if ( !SUCCESS( converted ) )
00524   {
00525     printf ( "color conversion failed\n" );
00526     return false;
00527   }
00528   result = true;
00529 
00530   return result;
00531 }
00532 
00533 
00534 bool GrabbingDevice::startCapture()
00535 {
00536 //  if(!SUCCESS(unicap_start_capture(m_Handle))) {
00537 //      TRACE_ERROR("Failed to start unicap capture");
00538 //  }
00539 
00540   unicap_status_t status;
00541   bool result = true;
00542 
00543   for ( uint i = 0; i < m_Buffers.size(); i++ )
00544   {
00545     status = unicap_queue_buffer ( m_Handle, m_Buffers.at ( i ) );
00546 
00547 //    if(!SUCCESS(status)) {
00548 //        TRACE_WARNING("Failed to queue unicap buffer #" << i);
00549 //    }
00550     result &= SUCCESS ( status );
00551   }
00552 
00553   return result;
00554 }
00555 
00556 
00557 
00558 bool GrabbingDevice::stopCapture()
00559 {
00560   unicap_status_t status;
00561   bool result;
00562   status = unicap_stop_capture ( m_Handle );
00563   result = SUCCESS ( status );
00564   return result;
00565 }
00566 
00567 
00568 
00569 bool GrabbingDevice::findFormatById ( unicap_format_t** _format, const uint _formatId, const uint _subformatId )
00570 {
00571   if ( ( _formatId > ( uint ) m_Formats.size() ) || ( _subformatId > ( uint ) m_Formats.at ( _formatId )->size_count ) )
00572     return false;
00573 
00574   m_Formats.at ( _formatId )->size.width = m_Formats.at ( _formatId )->sizes[_subformatId].width;
00575   m_Formats.at ( _formatId )->size.height = m_Formats.at ( _formatId )->sizes[_subformatId].height;
00576 
00577   *_format = m_Formats.at ( _formatId );
00578   return true;
00579 }
00580 
00581 
00582 
00583 bool GrabbingDevice::findPropertyById ( unicap_property_t** _property, const uint _id )
00584 {
00585   if ( _id > m_Properties.size() ) return false;
00586   *_property = m_Properties.at ( _id );
00587   return true;
00588 }
00589 
00590 
00591 
00592 bool GrabbingDevice::findPropertyByDesc ( unicap_property_t** _property, const string &_desc )
00593 {
00594   unicap_property_t* property = new unicap_property_t();
00595   string propname ( _desc );
00596 
00597   strncpy ( property->identifier, propname.c_str(), propname.length() );
00598 
00599   unicap_status_t status = unicap_get_property ( m_Handle, property );
00600   if ( ! SUCCESS ( status ) )
00601   {
00602     printf ( "sorry, property %s could not be found\n", propname.c_str() );
00603     return false;
00604   }
00605   *_property = property;
00606   return true;
00607 }
00608 
00609 
00610 
00611 bool GrabbingDevice::setProperty ( const string &_name, property_value_t &_value, bool _normalized )
00612 {
00613   unicap_property_t* property;
00614   bool result = findPropertyByDesc ( &property, _name );
00615 
00616   if ( !result ) return false;
00617 
00618   double value = 0, min = 0, max = 0, tmp = 0;
00619   bool found = false;
00620 
00621   switch ( property->type )
00622   {
00623 
00624     case UNICAP_PROPERTY_TYPE_RANGE:
00625       if ( _normalized )
00626       {
00627         min = property->range.min;
00628         max = property->range.max;
00629         value = _value.value * ( max - min ) + min;
00630       }
00631       else
00632       {
00633         value = _value.value;
00634       }
00635       property->value = value;
00636       break;
00637 
00638     case UNICAP_PROPERTY_TYPE_VALUE_LIST:
00639       if ( _normalized )
00640       {
00641         min = property->range.min;
00642         max = property->range.max;
00643         tmp = _value.value * ( max - min ) + min;
00644       }
00645       else
00646       {
00647         tmp = _value.value;
00648       }
00649 
00650       for ( int i = 0; ( ( i < property->value_list.value_count ) &&
00651                          ( property->value_list.values[i] <= tmp ) ); i++ )
00652       {
00653         value = property->value_list.values[i];
00654       }
00655       property->value = value;
00656       break;
00657 
00658     case UNICAP_PROPERTY_TYPE_MENU:
00659 
00660       for ( int i = 0; ( ( i < property->menu.menu_item_count ) && !found ); i++ )
00661       {
00662         if ( strcmp ( property->menu.menu_items[i], _value.menuItem ) == 0 )
00663         {
00664           found = true;
00665           strcpy ( property->menu_item, property->menu.menu_items[i] );
00666         }
00667       }
00668       if ( !found ) return false;
00669       break;
00670 
00671     case UNICAP_PROPERTY_TYPE_DATA:
00672       printf ( "UNICAP_PROPERTY_TYPE_DATA:sorry,not implemented yet\n" );
00673       return false;
00674       break;
00675 
00676     case UNICAP_PROPERTY_TYPE_FLAGS:
00677       printf ( "UNICAP_PROPERTY_TYPE_FLAGS:sorry,not implemented yet\n" );
00678       return false;
00679       break;
00680 
00681 
00682     case UNICAP_PROPERTY_TYPE_UNKNOWN:
00683       printf ( "unknown property type, dont know what to do\n" );
00684       return false;
00685       break;
00686   }
00687   // call function to set property
00688   return setProperty ( *property );
00689 }
00690 
00691 
00692 
00693 bool GrabbingDevice::prepareBuffers()
00694 {
00695   //TRACE_INFO( "Allocating "+toString( m_NumBuffers ) + " buffers of size " + toString( m_CurrentFormat->buffer_size ) );
00696 
00697   stopCapture();
00698 
00699   if ( ! ( m_CurrentFormat ) )
00700   {
00701     return false;
00702   }
00703 
00704   // delete previous data
00705   for ( uint i = 0; i < m_Buffers.size(); i++ )
00706   {
00707     free ( m_Buffers.at ( i )->data );
00708     delete m_Buffers.at ( i );
00709   }
00710   m_Buffers.clear();
00711 
00712   for ( uint numBuffers  = 0; numBuffers < m_NumBuffers; numBuffers++ )
00713   {
00714     #ifdef DEBUG
00715     printf ( "%s Line[%d] : (re)allocating memory for buffer %i  \n", __FILE__, __LINE__, numBuffers );
00716     #endif
00717     unicap_data_buffer_t *newBuffer = new unicap_data_buffer_t();
00718     newBuffer->data = ( byte* ) malloc ( m_CurrentFormat->buffer_size );
00719     memset ( newBuffer->data, 0x0, m_CurrentFormat->buffer_size );
00720     newBuffer->buffer_size = m_CurrentFormat->buffer_size;
00721 
00722     m_Buffers.push_back ( newBuffer );
00723   }
00724 
00725   return true;
00726 }
00727 
00728 
00729 
00730 bool GrabbingDevice::detectFormats()
00731 {
00732   // delete previous data
00733   for ( uint i = 0; i < m_Formats.size(); i++ )
00734   {
00735     delete m_Formats.at ( i );
00736   }
00737   m_Formats.clear();
00738 
00739   unicap_status_t status = STATUS_SUCCESS;
00740 
00741   for ( uint numFormats = 0; SUCCESS ( status ); numFormats++ )
00742   {
00743     unicap_format_t* newFormat = new unicap_format_t();
00744     status = unicap_enumerate_formats ( m_Handle, NULL, newFormat, numFormats );
00745 
00746 //     if ( newFormat->fourcc == UCIL_FOURCC( 'M', 'J', 'P', 'G' ) )
00747 //     {
00748 //       int w = newFormat->size.width;
00749 //       int h = newFormat->size.height;
00750 //       newFormat->buffer_size = w*h*3 + 65535;
00751 //       newFormat->bpp=24;
00752 //     }
00753 
00754     if ( SUCCESS ( status ) )
00755     {
00756       m_Formats.push_back ( newFormat );
00757     }
00758     else
00759     {
00760       delete newFormat;
00761     }
00762   }
00763 
00764   if (m_Formats.size() == 0)
00765 //    TRACE_ERROR("Failed to get video format");
00766 
00767 #ifdef DEBUG
00768   printf ( "%s Line[%d] : %i supported formats detected! \n", __FILE__, __LINE__, ( int ) m_Formats.size() );
00769 #endif
00770 
00771   detectProperties();
00772   return true;
00773 }
00774 
00775 
00776 
00777 bool GrabbingDevice::detectProperties()
00778 {
00779   // delete previous data
00780   for ( uint i = 0; i < m_Properties.size(); i++ )
00781   {
00782     delete m_Properties.at ( i );
00783   }
00784   m_Properties.clear();
00785 
00786   unicap_status_t status = STATUS_SUCCESS;
00787 
00788   for ( uint numProperties = 0; SUCCESS ( status ); numProperties++ )
00789   {
00790     unicap_property_t* newProperty = new unicap_property_t();
00791     status = unicap_enumerate_properties ( m_Handle, NULL, newProperty, numProperties );
00792 
00793     if ( SUCCESS ( status ) )
00794     {
00795       m_Properties.push_back ( newProperty );
00796     }
00797     else
00798     {
00799       delete newProperty;
00800     }
00801   }
00802 
00803 #ifdef DEBUG
00804   printf ( "%s Line[%d] : %i supported properties detected! \n",
00805            __FILE__, __LINE__, ( int ) m_Properties.size() );
00806 #endif
00807 
00808   return true;
00809 }
00810 
00811 
00812 
00813 
00814 string GrabbingDevice::getFormatsList()
00815 {
00816   int subformat = 0;
00817 
00818   ostringstream s;
00819   char str[65535];
00820 
00821   char blank[] = " ";
00822   sprintf ( str, "\n%5s | %25s | %17s | %15s | \n", "Index", "Identifier", "Resolution", "BitPerPixel" );
00823   s << str;
00824   sprintf ( str, "%5s | %25s | %17s | %15s | \n", blank, blank, blank, blank );
00825   s << str;
00826 
00827   for ( uint format = 0;  format < m_Formats.size(); format++ )
00828   {
00829     subformat = 0;
00830 
00831     if ( m_Formats.at ( format )->size_count <= 0 )
00832     {
00833       sprintf ( str, " %2i.%i | %25s | %10i x %4i | %15i | \n",
00834                 format,
00835                 subformat,
00836                 m_Formats.at ( format )->identifier,
00837                                m_Formats.at ( format )->size.width,
00838                                               m_Formats.at ( format )->size.height,
00839                                                   m_Formats.at ( format )->bpp );
00840       s << str;
00841     }
00842 
00843     for ( subformat = 0; subformat < m_Formats.at ( format )->size_count; subformat++ )
00844     {
00845       sprintf ( str, " %2i.%i | %25s | %10i x %4i | %15i | \n",
00846                 format,
00847                 subformat,
00848                 m_Formats.at ( format )->identifier,
00849                                m_Formats.at ( format )->sizes[subformat].width,
00850                                               m_Formats.at ( format )->sizes[subformat].height,
00851                                                   m_Formats.at ( format )->bpp );
00852       s << str;
00853     }
00854   }
00855 
00856   return s.str();
00857 }
00858 
00859 
00860 string GrabbingDevice::getPropertiesList()
00861 {
00862   const string modes[] = { "range", "value list", "menu", "data", "flags" };
00863 
00864   ostringstream s;
00865   char str[65535];
00866 
00867   sprintf ( str, "\n%5s|%25s|%25s|%10s|%15s|\n", "index", "identifier", "category", "relations", "type" );
00868   s << str;
00869   sprintf ( str, "%5s|%25s|%25s|%10s|%15s|\n", "", "", "", "", "" );
00870   s << str;
00871 
00872   for ( uint pid = 0; pid < m_Properties.size(); pid++ )
00873   {
00874     sprintf ( str, "%5i|%25s|%25s|%10i|%15s|\n",
00875               pid,
00876               m_Properties.at ( pid )->identifier,
00877                                 m_Properties.at ( pid )->category,
00878                                     m_Properties.at ( pid )->relations_count,
00879                                         modes[m_Properties.at ( pid )->type].c_str() );
00880     s << str;
00881   }
00882 
00883   return s.str();
00884 }
00885 
00886 
00887 string GrabbingDevice::getPropertyInfo ( const string &_desc )
00888 {
00889   unicap_property_t* property;
00890 
00891   bool result = findPropertyByDesc ( &property, _desc );
00892   if ( !result ) return "";
00893 
00894   ostringstream s;
00895 
00896   char* propertyName = property->identifier;
00897   s << "property name : " << propertyName << endl;
00898 
00899   switch ( property->type )
00900   {
00901     case UNICAP_PROPERTY_TYPE_RANGE:
00902       s << "property range: " << property->range.min << " - " << property->range.max << endl;
00903       s << " current value: " << property->value;
00904       break;
00905 
00906     case UNICAP_PROPERTY_TYPE_VALUE_LIST:
00907       s << "valid values are: ";
00908       for ( int i = 0; i < property->value_list.value_count; i++ )
00909       {
00910         if ( i > 0 ) {
00911           s << ", ";
00912         }
00913         s << property->value_list.values[i];
00914       }
00915       s << endl;
00916       s << " current value: " << property->value;
00917       break;
00918 
00919     case UNICAP_PROPERTY_TYPE_MENU:
00920       s << "valid values are: ";
00921       for ( int i = 0; i < property->value_list.value_count; i++ )
00922       {
00923         if ( i > 0 ) {
00924           s << ", ";
00925         }
00926         s << property->menu.menu_items[i];
00927       }
00928       s << endl;
00929       s << " current value: " << property->menu_item;
00930       break;
00931 
00932     case UNICAP_PROPERTY_TYPE_DATA:
00933     case UNICAP_PROPERTY_TYPE_FLAGS:
00934     case UNICAP_PROPERTY_TYPE_UNKNOWN:
00935     default:
00936       s << "Value type unsupported.";
00937       break;
00938   }
00939 
00940   return s.str();
00941 }
00942 


obj_rec_gui
Author(s): AGAS/agas@uni-koblenz.de
autogenerated on Mon Oct 6 2014 02:53:43