Frame.h
Go to the documentation of this file.
00001 /*=============================================================================
00002   Copyright (C) 2012 Allied Vision Technologies.  All Rights Reserved.
00003 
00004   Redistribution of this file, in original or modified form, without
00005   prior written consent of Allied Vision Technologies is prohibited.
00006 
00007 -------------------------------------------------------------------------------
00008 
00009   File:        Frame.h
00010 
00011   Description: Definition of class AVT::VmbAPI::Frame.
00012 
00013 -------------------------------------------------------------------------------
00014 
00015   THIS SOFTWARE IS PROVIDED BY THE AUTHOR "AS IS" AND ANY EXPRESS OR IMPLIED
00016   WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF TITLE,
00017   NON-INFRINGEMENT, MERCHANTABILITY AND FITNESS FOR A PARTICULAR  PURPOSE ARE
00018   DISCLAIMED.  IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, 
00019   INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 
00020   (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00021   LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED  
00022   AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR 
00023   TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 
00024   OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00025 
00026 =============================================================================*/
00027 
00028 #ifndef AVT_VMBAPI_FRAME_H
00029 #define AVT_VMBAPI_FRAME_H
00030 
00031 #include <VimbaC/Include/VimbaC.h>
00032 #include <VimbaCPP/Include/VimbaCPPCommon.h>
00033 #include <VimbaCPP/Include/SharedPointerDefines.h>
00034 #include <VimbaCPP/Include/IFrameObserver.h>
00035 #include <VimbaCPP/Include/AncillaryData.h>
00036 #include <vector>
00037 
00038 namespace AVT {
00039 namespace VmbAPI {
00040 
00041 class Frame 
00042 {
00043   friend class Camera;
00044 
00045   public:
00046     //
00047     // Method:      Frame constructor
00048     //
00049     // Purpose:     Creates an instance of class Frame of a certain size
00050     //
00051     // Parameters:  [in ]   VmbInt64_t      bufferSize  The size of the underlying buffer
00052     //
00053     IMEXPORT explicit Frame( VmbInt64_t bufferSize );
00054 
00055     //
00056     // Method:      Frame constructor
00057     //
00058     // Purpose:     Creates an instance of class Frame with the given user buffer of the given size
00059     //
00060     // Parameters:  [in ]   VmbUchar_t*     pBuffer     A pointer to an allocated buffer
00061     // Parameters:  [in ]   VmbInt64_t      bufferSize  The size of the underlying buffer
00062     //
00063     IMEXPORT Frame( VmbUchar_t *pBuffer, VmbInt64_t bufferSize );
00064 
00065     //
00066     // Method:      Frame destructor
00067     //
00068     // Purpose:     Destroys an instance of class Frame
00069     //
00070     IMEXPORT ~Frame();
00071 
00072     //
00073     // Method:      RegisterObserver()
00074     //
00075     // Purpose:     Registers an observer that will be called whenever a new frame arrives
00076     //
00077     // Parameters:  [in ]   const IFrameObserverPtr&   pObserver   An object that implements the IObserver interface
00078     //
00079     // Returns:
00080     //
00081     //  - VmbErrorSuccess:      If no error
00082     //  - VmbErrorBadParameter: "pObserver" is NULL.
00083     //  - VmbErrorResources:    The observer was in use
00084     //
00085     // Details:     As new frames arrive, the observer's FrameReceived method will be called.
00086     //              Only one observer can be registered.
00087     //
00088     IMEXPORT VmbErrorType RegisterObserver( const IFrameObserverPtr &pObserver );
00089 
00090     //
00091     // Method:      UnregisterObserver()
00092     //
00093     // Purpose:     Unregisters the observer that was called whenever a new frame arrived
00094     //
00095     IMEXPORT VmbErrorType UnregisterObserver();
00096 
00097     //
00098     // Method:      GetAncillaryData()
00099     //
00100     // Purpose:     Returns the part of a frame that describes the chunk data as an object
00101     //
00102     // Parameters:  [out]   AncillaryDataPtr&        pAncillaryData      The wrapped chunk data
00103     //
00104     // Returns:
00105     //
00106     //  - VmbErrorSuccess:      If no error
00107     //  - VmbErrorNotFound:     No chunk data present
00108     //
00109     IMEXPORT VmbErrorType GetAncillaryData( AncillaryDataPtr &pAncillaryData );
00110 
00111     //
00112     // Method:      GetAncillaryData()
00113     //
00114     // Purpose:     Returns the part of a frame that describes the chunk data as an object
00115     //
00116     // Parameters:  [out]   ConstAncillaryDataPtr&    pAncillaryData     The wrapped chunk data
00117     //
00118     // Returns:
00119     //
00120     //  - VmbErrorSuccess:      If no error
00121     //  - VmbErrorNotFound:     No chunk data present
00122     //
00123     IMEXPORT VmbErrorType GetAncillaryData( ConstAncillaryDataPtr &pAncillaryData ) const;
00124 
00125     //
00126     // Method:      GetBuffer()
00127     //
00128     // Purpose:     Returns the complete buffer including image and chunk data
00129     //
00130     // Parameters:  [out]   VmbUchar_t*      pBuffer        A pointer to the buffer
00131     //
00132     // Returns:
00133     //
00134     //  - VmbErrorSuccess:      If no error
00135     //
00136     IMEXPORT VmbErrorType GetBuffer( VmbUchar_t* &pBuffer );
00137 
00138     //
00139     // Method:      GetBuffer()
00140     //
00141     // Purpose:     Returns the complete buffer including image and chunk data
00142     //
00143     // Parameters:  [out]   const VmbUchar_t*      pBuffer  A pointer to the buffer
00144     //
00145     // Returns:
00146     //
00147     //  - VmbErrorSuccess:      If no error
00148     //
00149     IMEXPORT VmbErrorType GetBuffer( const VmbUchar_t* &pBuffer ) const;
00150 
00151     //
00152     // Method:      GetImage()
00153     //
00154     // Purpose:     Returns only the image data
00155     //
00156     // Parameters:  [out]   VmbUchar_t*         pBuffer     A pointer to the buffer
00157     //
00158     // Returns:
00159     //
00160     //  - VmbErrorSuccess:      If no error
00161     //
00162     IMEXPORT VmbErrorType GetImage( VmbUchar_t* &pBuffer );
00163 
00164     //
00165     // Method:      GetImage()
00166     //
00167     // Purpose:     Returns only the image data
00168     //
00169     // Parameters:  [out]   const VmbUchar_t*    pBuffer    A pointer to the buffer
00170     //
00171     // Returns:
00172     //
00173     //  - VmbErrorSuccess:      If no error
00174     //
00175     IMEXPORT VmbErrorType GetImage( const VmbUchar_t* &pBuffer ) const;
00176 
00177     //
00178     // Method:      GetReceiveStatus()
00179     //
00180     // Purpose:     Returns the receive status of a frame
00181     //
00182     // Parameters:  [out]   VmbFrameStatusType&   status    The receive status
00183     //
00184     // Returns:
00185     //
00186     //  - VmbErrorSuccess:      If no error
00187     //
00188     IMEXPORT VmbErrorType GetReceiveStatus( VmbFrameStatusType &status ) const;
00189     
00190     //
00191     // Method:      GetImageSize()
00192     //
00193     // Purpose:     Returns the memory size of the image
00194     //
00195     // Parameters:  [out]   VmbUint32_t&    imageSize       The size in bytes
00196     //
00197     // Returns:
00198     //
00199     //  - VmbErrorSuccess:      If no error
00200     //
00201     IMEXPORT VmbErrorType GetImageSize( VmbUint32_t &imageSize ) const;
00202     
00203     //
00204     // Method:      GetAncillarySize()
00205     //
00206     // Purpose:     Returns memory size of the chunk data
00207     //
00208     // Parameters:  [out]   VmbUint32_t&    ancillarySize   The size in bytes
00209     //
00210     // Returns:
00211     //
00212     //  - VmbErrorSuccess:      If no error
00213     //
00214     IMEXPORT VmbErrorType GetAncillarySize( VmbUint32_t &ancillarySize ) const;
00215     
00216     //
00217     // Method:      GetBufferSize()
00218     //
00219     // Purpose:     Returns the memory size of the frame buffer holding 
00220     //              both the image data and the ancillary data
00221     //
00222     // Parameters:  [out]   VmbUint32_t&    bufferSize      The size in bytes
00223     //
00224     // Returns:
00225     //
00226     //  - VmbErrorSuccess:      If no error
00227     //
00228     IMEXPORT VmbErrorType GetBufferSize( VmbUint32_t &bufferSize ) const;
00229 
00230     //
00231     // Method:      GetPixelFormat()
00232     //
00233     // Purpose:     Returns the GenICam pixel format
00234     //
00235     // Parameters:  [out]   VmbPixelFormatType&      pixelFormat    The GenICam pixel format
00236     //
00237     // Returns:
00238     //
00239     //  - VmbErrorSuccess:      If no error
00240     //
00241     IMEXPORT VmbErrorType GetPixelFormat( VmbPixelFormatType &pixelFormat ) const;
00242 
00243     //
00244     // Method:      GetWidth()
00245     //
00246     // Purpose:     Returns the width of the image
00247     //
00248     // Parameters:  [out]   VmbUint32_t&    width       The width in pixels
00249     //
00250     // Returns:
00251     //
00252     //  - VmbErrorSuccess:      If no error
00253     //
00254     IMEXPORT VmbErrorType GetWidth( VmbUint32_t &width ) const;
00255 
00256     //
00257     // Method:      GetHeight()
00258     //
00259     // Purpose:     Returns the height of the image
00260     //
00261     // Parameters:  [out]   VmbUint32_t&    height       The height in pixels
00262     //
00263     // Returns:
00264     //
00265     //  - VmbErrorSuccess:      If no error
00266     //
00267     IMEXPORT VmbErrorType GetHeight( VmbUint32_t &height ) const;
00268 
00269     //
00270     // Method:      GetOffsetX()
00271     //
00272     // Purpose:     Returns the x offset of the image
00273     //
00274     // Parameters:  [out]   VmbUint32_t&    offsetX     The x offset in pixels
00275     //
00276     // Returns:
00277     //
00278     //  - VmbErrorSuccess:      If no error
00279     //
00280     IMEXPORT VmbErrorType GetOffsetX( VmbUint32_t &offsetX ) const;
00281 
00282     //
00283     // Method:      GetOffsetY()
00284     //
00285     // Purpose:     Returns the y offset of the image
00286     //
00287     // Parameters:  [out]   VmbUint32_t&    offsetY     The y offset in pixels
00288     //
00289     // Returns:
00290     //
00291     //  - VmbErrorSuccess:      If no error
00292     //
00293     IMEXPORT VmbErrorType GetOffsetY( VmbUint32_t &offsetY ) const;
00294 
00295     //
00296     // Method:      GetFrameID()
00297     //
00298     // Purpose:     Returns the frame ID
00299     //
00300     // Parameters:  [out]   VmbUint64_t&     frameID    The frame ID
00301     //
00302     // Returns:
00303     //
00304     //  - VmbErrorSuccess:      If no error
00305     //
00306     IMEXPORT VmbErrorType GetFrameID( VmbUint64_t &frameID ) const;
00307 
00308     //
00309     // Method:      GetTimeStamp()
00310     //
00311     // Purpose:     Returns the time stamp
00312     //
00313     // Parameters:  [out]   VmbUint64_t&     timestamp  The time stamp
00314     //
00315     // Returns:
00316     //
00317     //  - VmbErrorSuccess:      If no error
00318     //
00319     IMEXPORT VmbErrorType GetTimestamp( VmbUint64_t &timestamp ) const;
00320 
00321     bool GetObserver( IFrameObserverPtr &observer ) const;
00322 
00323   private:
00324     struct Impl;
00325     Impl *m_pImpl;
00326 
00327     // No default ctor
00328     Frame();
00329     // No copy ctor
00330     Frame( Frame& );
00331     // No assignment operator
00332     Frame& operator=( const Frame& );
00333 };
00334 
00335 typedef std::vector<FramePtr> FramePtrVector;
00336 
00337 }} // namespace AVT::VmbAPI
00338 
00339 #endif


avt_vimba_camera
Author(s): Miquel Massot , Allied Vision Technologies
autogenerated on Thu Jun 6 2019 18:23:39