Camera.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:        Camera.h
00010 
00011   Description: Definition of class AVT::VmbAPI::Camera.
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_CAMERA_H
00029 #define AVT_VMBAPI_CAMERA_H
00030 
00031 #include <vector>
00032 #include <string>
00033 
00034 #include <VimbaC/Include/VimbaC.h>
00035 #include <VimbaCPP/Include/VimbaCPPCommon.h>
00036 #include <VimbaCPP/Include/IRegisterDevice.h>
00037 #include <VimbaCPP/Include/FeatureContainer.h>
00038 #include <VimbaCPP/Include/Frame.h>
00039 #include <VimbaCPP/Include/IFrameObserver.h>
00040 #include <VimbaCPP/Include/SharedPointerDefines.h>
00041 
00042 namespace AVT {
00043 namespace VmbAPI {
00044 
00045 typedef std::vector<CameraPtr> CameraPtrVector;
00046 
00047 class Camera : public FeatureContainer, public IRegisterDevice 
00048 {
00049   public:
00050     //
00051     // Method:      Camera constructor
00052     //
00053     // Purpose:     Creates an instance of class camera
00054     //
00055     // Parameters:
00056     //
00057     // [in ]    const char      *pID            The ID of the camera    
00058     // [in ]    const char      *pName          The name of the camera
00059     // [in ]    const char      *pModel,        The model name of the camera
00060     // [in ]    const char      *pSerialNumber  The serial number of the camera
00061     // [in ]    const char      *pInterfaceID   The ID of the interface the camera is connected to
00062     // [in ]    VmbInterfaceType interfaceType  The type of the interface the camera is connected to
00063     //
00064     // Details:   The ID might be one of the following:"IP:169.254.12.13", "MAC:000f31000001",
00065     //            or a plain serial number: "1234567890".
00066     //
00067     IMEXPORT Camera(    const char *pID,
00068                         const char *pName,
00069                         const char *pModel,
00070                         const char *pSerialNumber,
00071                         const char *pInterfaceID,
00072                         VmbInterfaceType interfaceType );
00073 
00074     //
00075     // Method:      Camera destructor
00076     //
00077     // Purpose:     Destroys an instance of class camera
00078     //
00079     // Details:     Destroying a camera implicitly closes it beforehand.
00080     //
00081     IMEXPORT virtual ~Camera();
00082 
00083     //
00084     // Method:      Open()
00085     //
00086     // Purpose:     Opens the specified camera.
00087     //
00088     // Parameters:
00089     //
00090     //  [in ]  VmbAccessMode_t  accessMode      Access mode determines the amount of control you have on the camera
00091     //
00092     // Returns:
00093     //
00094     //  - VmbErrorSuccess:       If no error
00095     //  - VmbErrorApiNotStarted: VmbStartup() was not called before the current command
00096     //  - VmbErrorNotFound:      The designated camera cannot be found
00097     //  - VmbErrorInvalidAccess: Operation is invalid with the current access mode
00098     //
00099     // Details:   A camera may be opened in a specific access mode. This mode determines
00100     //            the amount of control you have on a camera.
00101     //  
00102     IMEXPORT virtual VmbErrorType Open( VmbAccessModeType accessMode );
00103 
00104     //
00105     // Method:      Close()
00106     //
00107     // Purpose:     Close the specified camera.
00108     //
00109     // Returns:
00110     //
00111     //  - VmbErrorSuccess:       If no error
00112     //  - VmbErrorApiNotStarted: VmbStartup() was not called before the current command
00113     //
00114     // Details:     Depending on the access mode this camera mode was opened in, events are killed,
00115     //              callbacks are unregistered, the frame queue is cleared, and camera control is released.
00116     //
00117     IMEXPORT virtual VmbErrorType Close();
00118 
00119     //
00120     // Method:      GetID()
00121     //
00122     // Purpose:     Gets the ID of a camera.
00123     //
00124     // Parameters:  [out]   std::string     &ID         The ID of the camera
00125     //
00126     // Returns:
00127     //  - VmbErrorSuccess:       If no error
00128     //
00129     //              This information remains static throughout the object's lifetime
00130     //
00131     VmbErrorType GetID( std::string &ID ) const;
00132 
00133     //
00134     // Method:      GetName()
00135     //
00136     // Purpose:     Gets the name of a camera.
00137     //
00138     // Parameters:  [out]   std::string     &name         The name of the camera
00139     //
00140     // Returns:
00141     //  - VmbErrorSuccess:       If no error
00142     //
00143     //              This information remains static throughout the object's lifetime
00144     //
00145     VmbErrorType GetName( std::string &name ) const;
00146     
00147     //
00148     // Method:      GetModel()
00149     //
00150     // Purpose:     Gets the model name of a camera.
00151     //
00152     // Parameters:  [out]   std::string     &model         The model name of the camera
00153     //
00154     // Returns:
00155     //  - VmbErrorSuccess:       If no error
00156     //
00157     //              This information remains static throughout the object's lifetime
00158     //
00159     VmbErrorType GetModel( std::string &model ) const;
00160 
00161     //
00162     // Method:      GetSerialNumber()
00163     //
00164     // Purpose:     Gets the serial number of a camera.
00165     //
00166     // Parameters:  [out]   std::string     &serialNumber         The serial number of the camera
00167     //
00168     // Returns:
00169     //  - VmbErrorSuccess:       If no error
00170     //
00171     //              This information remains static throughout the object's lifetime
00172     //
00173     VmbErrorType GetSerialNumber( std::string &serialNumber ) const;
00174 
00175     //
00176     // Method:      GetInterfaceID()
00177     //
00178     // Purpose:     Gets the interface ID of a camera.
00179     //
00180     // Parameters:  [out]   std::string     &interfaceID         The interface ID of the camera
00181     //
00182     // Returns:
00183     //  - VmbErrorSuccess:       If no error
00184     //
00185     //              This information remains static throughout the object's lifetime
00186     //
00187     VmbErrorType GetInterfaceID( std::string &interfaceID ) const;
00188 
00189     //
00190     // Method:      GetInterfaceType()
00191     //
00192     // Purpose:     Gets the type of the interface the camera is connected to. And therefore the type of the camera itself.
00193     //
00194     // Parameters:  [out]   VmbInterfaceType    &interfaceType The interface type of the camera
00195     //
00196     // Returns:
00197     //  - VmbErrorSuccess:       If no error
00198     //
00199     IMEXPORT VmbErrorType GetInterfaceType( VmbInterfaceType &interfaceType ) const;
00200 
00201     //
00202     // Method:      GetPermittedAccess()
00203     //
00204     // Purpose:     Gets the access mode of an camera.
00205     //
00206     // Parameters:  [out]   VmbAccessModeType   &permittedAccess The possible access mode of the camera
00207     //
00208     // Returns:
00209     //  - VmbErrorSuccess:       If no error
00210     //
00211     IMEXPORT VmbErrorType GetPermittedAccess( VmbAccessModeType &permittedAccess ) const;
00212 
00213     //
00214     // Method:      ReadRegisters()
00215     //
00216     // Purpose:     Reads one or more registers consecutively. The amount of registers to read is determined by the amount of provided addresses.
00217     //
00218     // Parameters:  [in ]   Uint64Vector     &addresses  A list of register addresses
00219     //              [out]   Uint64Vector     &buffer     The returned data as vector
00220     //
00221     // Returns:
00222     //  - VmbErrorSuccess:      If all requested registers have been read
00223     //  - VmbErrorIncomplete:   If at least one, but not all registers have been read. See overload ReadRegisters( const Uint64Vector &addresses, Uint64Vector &buffer, VmbUint32_t &completeReads ).
00224     //
00225     virtual VmbErrorType ReadRegisters( const Uint64Vector &addresses, Uint64Vector &buffer ) const;
00226     
00227     //
00228     // Method:      ReadRegisters()
00229     //
00230     // Purpose:     Reads one or more registers consecutively. The amount of registers to read is determined by the amount of provided addresses.
00231     //
00232     // Parameters:  [in ]   const Uint64Vector   &addresses       A list of register addresses
00233     //              [out]   Uint64Vector         &buffer          The returned data as vector
00234     //              [out]   VmbUint64_t          &completedReads  The number of successfully read registers
00235     //
00236     // Returns:
00237     //  - VmbErrorSuccess:      If all requested registers have been read
00238     //  - VmbErrorIncomplete:   If at least one, but not all registers have been read.
00239     //
00240     virtual VmbErrorType ReadRegisters( const Uint64Vector &addresses, Uint64Vector &buffer, VmbUint32_t &completedReads ) const;
00241     
00242     //
00243     // Method:      WriteRegisters()
00244     //
00245     // Purpose:     Writes one or more registers consecutively. The amount of registers to write is determined by the amount of provided addresses.
00246     //
00247     // Parameters:  [in]    Uint64Vector     &addresses  A list of register addresses
00248     //              [in]    Uint64Vector     &buffer     The data to write as vector
00249     //
00250     // Returns:
00251     //  - VmbErrorSuccess:      If all requested registers have been written
00252     //  - VmbErrorIncomplete:   If at least one, but not all registers have been written. See overload WriteRegisters( const Uint64Vector &addresses, Uint64Vector &buffer, VmbUint32_t &completeWrites ).
00253     //
00254     virtual VmbErrorType WriteRegisters( const Uint64Vector &addresses, const Uint64Vector &buffer );
00255 
00256     //
00257     // Method:      WriteRegisters()
00258     //
00259     // Purpose:     Writes one or more registers consecutively. The amount of registers to write is determined by the amount of provided addresses.
00260     //
00261     // Parameters:  [in ]   Uint64Vector     &addresses       A list of register addresses
00262     //              [in ]   Uint64Vector     &buffer          The data to write as vector
00263     //              [out]   VmbUint64_t      &completedWrites The number of successfully read registers
00264     //
00265     // Returns:
00266     //  - VmbErrorSuccess:      If all requested registers have been written
00267     //  - VmbErrorIncomplete:   If at least one, but not all registers have been written.
00268     //
00269     virtual VmbErrorType WriteRegisters( const Uint64Vector &addresses, const Uint64Vector &buffer, VmbUint32_t &completedWrites );
00270 
00271     //
00272     // Method:      ReadMemory()
00273     //
00274     // Purpose:     Reads a block of memory. The number of bytes to read is determined by the size of the provided buffer.
00275     //
00276     // Parameters:  [in ]   VmbUint64_t     &address    The address to read from
00277     //              [out]   UcharVector     &buffer     The returned data as vector
00278     //
00279     // Returns:
00280     //  - VmbErrorSuccess:      If all requested bytes have been read
00281     //  - VmbErrorIncomplete:   If at least one, but not all bytes have been read. See overload ReadMemory( const VmbUint64_t &address, UcharVector &buffer, VmbUint32_t &completeReads ).
00282     //
00283     virtual VmbErrorType ReadMemory( const VmbUint64_t &address, UcharVector &buffer ) const;
00284 
00285     //
00286     // Method:      ReadMemory()
00287     //
00288     // Purpose:     Reads a block of memory. The number of bytes to read is determined by the size of the provided buffer.
00289     //
00290     // Parameters:  [in]    VmbUint64_t     &address        The address to read from
00291     //              [out]   UcharVector     &buffer         The returned data as vector
00292     //              [out]   VmbUint32_t     &completeReads  The number of successfully read bytes
00293     //
00294     // Returns:
00295     //  - VmbErrorSuccess:      If all requested bytes have been read
00296     //  - VmbErrorIncomplete:   If at least one, but not all bytes have been read.
00297     //
00298     virtual VmbErrorType ReadMemory( const VmbUint64_t &address, UcharVector &buffer, VmbUint32_t &completeReads ) const;
00299 
00300     //
00301     // Method:      WriteMemory()
00302     //
00303     // Purpose:     Writes a block of memory. The number of bytes to write is determined by the size of the provided buffer.
00304     //
00305     // Parameters:  [in]    VmbUint64_t     &address    The address to write to
00306     //              [in]    UcharVector     &buffer     The data to write as vector
00307     //
00308     // Returns:
00309     //  - VmbErrorSuccess:      If all requested bytes have been written
00310     //  - VmbErrorIncomplete:   If at least one, but not all bytes have been written. See overload ReadMemory( const VmbUint64_t &address, UcharVector &buffer, VmbUint32_t &completeWrites ).
00311     //
00312     virtual VmbErrorType WriteMemory( const VmbUint64_t &address, const UcharVector &buffer );
00313 
00314     //
00315     // Method:      WriteMemory()
00316     //
00317     // Purpose:     Writes a block of memory. The number of bytes to write is determined by the size of the provided buffer.
00318     //
00319     // Parameters:  [in]    VmbUint64_t     &address        The address to write to
00320     //              [in]    UcharVector     &buffer         The data to write as vector
00321     //              [out]   VmbUint32_t     &completeWrites The number of successfully written bytes
00322     //
00323     // Returns:
00324     //  - VmbErrorSuccess:      If all requested bytes have been written
00325     //  - VmbErrorIncomplete:   If at least one, but not all bytes have been written.
00326     //
00327     virtual VmbErrorType WriteMemory( const VmbUint64_t &address, const UcharVector &buffer, VmbUint32_t &sizeComplete );
00328 
00329     //
00330     // Method:      AcquireSingleImage()
00331     //
00332     // Purpose:     Gets one image synchronously.
00333     //
00334     // Parameters:  [out]   FramePtr        &frame          The frame that gets filled
00335     //              [in ]   VmbUint32_t     timeout         The time to wait until the frame got filled
00336     //
00337     IMEXPORT VmbErrorType AcquireSingleImage( FramePtr &frame, VmbUint32_t timeout );
00338 
00339     //
00340     // Method:      AcquireMultipleImages()
00341     //
00342     // Purpose:     Gets multiple images synchronously.
00343     //
00344     // Parameters:  [out]   FramePtrVector  &frames         The frames that get filled
00345     //              [in ]   VmbUint32_t     timeout         The time to wait until one frame got filled
00346     //
00347     VmbErrorType AcquireMultipleImages( FramePtrVector &frames, VmbUint32_t timeout );
00348 
00349     //
00350     // Method:      AcquireMultipleImages()
00351     //
00352     // Purpose:     Gets multiple images synchronously.
00353     //
00354     // Parameters:  [out]   FramePtrVector  &frames             The frames that get filled
00355     //              [in ]   VmbUint32_t     timeout             The time to wait until one frame got filled
00356     //              [out]   VmbUint32_t     &numFramesCompleted The number of frames that were filled completely
00357     //
00358     // Details:     The size of the frame vector determines the number of frames to use
00359     //
00360     VmbErrorType AcquireMultipleImages( FramePtrVector &frames, VmbUint32_t timeout, VmbUint32_t &numFramesCompleted );
00361 
00362     //
00363     // Method:      StartContinuousImageAcquisition()
00364     //
00365     // Purpose:     Starts streaming and allocates the needed frames
00366     //
00367     // Parameters:  [in ]   VmbUint32_t                 bufferCount     The number of frames to use
00368     //              [out]   const IFrameObserverPtr     &pObserver      The observe to use on arrival of new frames
00369     //
00370     // Returns:
00371     //
00372     //  - VmbErrorSuccess:        If no error
00373     //  - VmbErrorDeviceNotOpen:  The camera has not been opened before
00374     //  - VmbErrorApiNotStarted:  VmbStartup() was not called before the current command
00375     //  - VmbErrorBadHandle:      The given handle is not valid
00376     //  - VmbErrorInvalidAccess:  Operation is invalid with the current access mode
00377     //
00378     IMEXPORT VmbErrorType StartContinuousImageAcquisition( int bufferCount, const IFrameObserverPtr &pObserver );
00379 
00380     //
00381     // Method:      StopContinuousImageAcquisition()
00382     //
00383     // Purpose:     Stops streaming and frees the needed frames
00384     //
00385     IMEXPORT VmbErrorType StopContinuousImageAcquisition();
00386 
00387     //
00388     // Method:      AnnounceFrame()
00389     //
00390     // Purpose:     Announces a frame to the API that may be queued for frame capturing later
00391     //
00392     // Parameters:
00393     //
00394     //  [in ]  const FramePtr    &pFrame         Shared pointer to a frame to announce
00395     //
00396     // Returns:
00397     //
00398     //  - VmbErrorSuccess:       If no error
00399     //  - VmbErrorApiNotStarted: VmbStartup() was not called before the current command
00400     //  - VmbErrorBadHandle:     The given handle is not valid
00401     //  - VmbErrorStructSize:    The given struct size is not valid for this version of the API
00402     //
00403     // Details:     Allows some preparation for frames like DMA preparation depending on the transport layer.
00404     //              The order in which the frames are announced is not taken in consideration by the API.
00405     //
00406     IMEXPORT VmbErrorType AnnounceFrame( const FramePtr &pFrame );
00407     
00408     //
00409     // Method:      RevokeFrame()
00410     //
00411     // Purpose:     Revoke a frame from the API.
00412     //
00413     // Parameters:
00414     //
00415     //  [in ]  const FramePtr    &pFrame         Shared pointer to a frame that is to be removed from the list of announced frames
00416     //
00417     // Returns:
00418     //
00419     //  - VmbErrorSuccess:       If no error
00420     //  - VmbErrorApiNotStarted: VmbStartup() was not called before the current command
00421     //  - VmbErrorBadHandle:     The given frame pointer is not valid
00422     //  - VmbErrorStructSize:    The given struct size is not valid for this version of the API
00423     //
00424     // Details:    The referenced frame is removed from the pool of frames for capturing images.
00425     //
00426     IMEXPORT VmbErrorType RevokeFrame( const FramePtr &pFrame );
00427 
00428     //
00429     // Method:      RevokeAllFrames()
00430     //
00431     // Purpose:     Revoke all frames assigned to this certain camera
00432     //
00433     // Returns:
00434     //
00435     //  - VmbErrorSuccess:       If no error
00436     //  - VmbErrorApiNotStarted: VmbStartup() was not called before the current command
00437     //  - VmbErrorBadHandle:     The given handle is not valid
00438     //
00439     IMEXPORT VmbErrorType RevokeAllFrames();
00440     
00441     //
00442     // Method:      QueueFrame()
00443     //
00444     // Purpose:     Queues a frame that may be filled during frame capturing
00445     //
00446     // Parameters:
00447     //
00448     //  [in ]  const FramePtr    &frame     A shared pointer to a frame
00449     //
00450     // Returns:
00451     //
00452     //  - VmbErrorSuccess:       If no error
00453     //  - VmbErrorApiNotStarted: Startup was not called before the current command
00454     //  - VmbErrorBadHandle:     The given frame is not valid
00455     //  - VmbErrorStructSize:    The given struct size is not valid for this version of the API
00456     //
00457     // Details:     The given frame is put into a queue that will be filled sequentially.
00458     //              The order in which the frames are filled is determined by the order in which they are queued.
00459     //              If the frame was announced with AnnounceFrame() before, the application
00460     //              has to take care that the frame is also revoked by calling RevokeFrame() or RevokeAll()
00461     //              when cleaning up.
00462     //
00463     IMEXPORT VmbErrorType QueueFrame( const FramePtr &frame );
00464 
00465     //
00466     // Method:      FlushQueue()
00467     //
00468     // Purpose:     Flushes the capture queue.
00469     //
00470     // Returns:
00471     //
00472     //  - VmbErrorSuccess:       If no error
00473     //  - VmbErrorApiNotStarted: Startup was not called before the current command
00474     //  - VmbErrorBadHandle:     The given handle is not valid
00475     //
00476     // Details:     All the currently queued frames will be returned to the user, leaving no frames in the input queue.
00477     //              After this call, no frame notification will occur until frames are queued again.
00478     //
00479     IMEXPORT VmbErrorType FlushQueue();
00480     
00481     //
00482     // Method:      StartCapture()
00483     //
00484     // Purpose:     Prepare the API for incoming frames from this camera.
00485     //
00486     // Returns:
00487     //
00488     //  - VmbErrorSuccess:       If no error
00489     //  - VmbErrorApiNotStarted: VmbStartup() was not called before the current command
00490     //  - VmbErrorBadHandle:     The given handle is not valid
00491     //  - VmbErrorDeviceNotOpen: Camera was not opened for usage
00492     //  - VmbErrorInvalidAccess: Operation is invalid with the current access mode
00493     //
00494     IMEXPORT VmbErrorType StartCapture();
00495 
00496     //
00497     // Method:      EndCapture()
00498     //
00499     // Purpose:     Stop the API from being able to receive frames from this camera.
00500     //
00501     // Returns:
00502     //
00503     //  - VmbErrorSuccess:       If no error
00504     //  - VmbErrorApiNotStarted: VmbStartup() was not called before the current command
00505     //  - VmbErrorBadHandle:     The given handle is not valid
00506     //
00507     // Details:     Consequences of VmbCaptureEnd():
00508     //                  - The frame queue is flushed
00509     //                  - The frame callback will not be called any more
00510     //
00511     IMEXPORT VmbErrorType EndCapture();
00512 
00513   private:
00514     // Default ctor
00515     Camera();
00516 
00517     // Copy ctor
00518     Camera ( const Camera& );
00519 
00520     // Assignment operator
00521     Camera& operator=( const Camera& );
00522 
00523     struct Impl;
00524     Impl *m_pImpl;
00525 
00526     // Array functions to pass data across DLL boundaries
00527     IMEXPORT VmbErrorType GetID( char * const pID, VmbUint32_t &length ) const;
00528     IMEXPORT VmbErrorType GetName( char * const pName, VmbUint32_t &length ) const;
00529     IMEXPORT VmbErrorType GetModel( char * const pModelName, VmbUint32_t &length ) const;
00530     IMEXPORT VmbErrorType GetSerialNumber( char * const pSerial, VmbUint32_t &length ) const;
00531     IMEXPORT VmbErrorType GetInterfaceID( char * const pInterfaceID, VmbUint32_t &length ) const;
00532     IMEXPORT VmbErrorType AcquireMultipleImages( FramePtr *pFrames, VmbUint32_t size, VmbUint32_t nTimeout, VmbUint32_t *pNumFramesCompleted );
00533     IMEXPORT virtual VmbErrorType ReadRegisters( const VmbUint64_t *pAddressArray, VmbUint32_t addressSize, VmbUint64_t *pDataArray, VmbUint32_t *pCompletedReads ) const;
00534     IMEXPORT virtual VmbErrorType WriteRegisters( const VmbUint64_t *pAddressArray, VmbUint32_t addressSize, const VmbUint64_t *pDataArray, VmbUint32_t *pCompletedWrites );
00535     IMEXPORT virtual VmbErrorType ReadMemory( VmbUint64_t address, VmbUchar_t *pBuffer, VmbUint32_t bufferSize, VmbUint32_t *pSizeComplete ) const;
00536     IMEXPORT virtual VmbErrorType WriteMemory( VmbUint64_t address, const VmbUchar_t *pBuffer, VmbUint32_t bufferSize, VmbUint32_t *pSizeComplete );
00537 };
00538 
00539 #include <VimbaCPP/Include/Camera.hpp>
00540 
00541 }} // namespace AVT::VmbAPI
00542 
00543 #endif


avt_vimba_camera
Author(s): Miquel Massot , Allied Vision Technologies
autogenerated on Thu Aug 27 2015 12:29:49