prosilica.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #ifndef PROSILICA_H
00036 #define PROSILICA_H
00037 
00038 #include <stdexcept>
00039 #include <string>
00040 #include <sstream>
00041 #include <boost/function.hpp>
00042 #include <boost/thread.hpp>
00043 
00044 // PvApi.h isn't aware of the usual detection macros
00045 //  these include support for i386, x86_64, and arm, on Linux and OSX
00046 #define _LINUX
00047 #define _x86
00048 #include <prosilica_gige_sdk/PvApi.h>
00049 #undef _LINUX
00050 #undef _x86
00051 
00052 
00053 template <class T>
00054 inline std::string to_string (const T& t)
00055 {
00056     std::stringstream ss;
00057     ss << t;
00058     return ss.str();
00059 }
00060 
00061 namespace prosilica {
00062 
00063 struct ProsilicaException : public std::runtime_error
00064 {
00065   tPvErr error_code;
00066   
00067   ProsilicaException(tPvErr code, const char* msg)
00068     : std::runtime_error(msg), error_code(code)
00069   {}
00070 };
00071 struct CameraInfo
00072 {
00073     std::string serial;
00074     std::string name;
00075     std::string guid;
00076     std::string ip_address;
00077     bool access;
00078 };
00079 
00080 void init();                  // initializes API
00081 void fini();                  // releases internal resources
00082 size_t numCameras();          // number of cameras found
00083 uint64_t getGuid(size_t i);   // camera ids
00084 std::vector<CameraInfo> listCameras(); // get list of cameras available
00085 std::string getIPAddress(uint64_t guid); //get ip address data from guid
00086 
00089 enum FrameStartTriggerMode
00090 {
00091   Freerun, 
00092   SyncIn1, 
00093   SyncIn2, 
00094   FixedRate, 
00095   Software,
00096   None
00097 };
00098 
00099 enum AcquisitionMode
00100 {
00101   Continuous,
00102   SingleFrame,
00103   MultiFrame,
00104   Recorder
00105 };
00106 
00107 enum AutoSetting
00108 {
00109   Manual,
00110   Auto,
00111   AutoOnce
00112 };
00113 
00114 class Camera
00115 {
00116 public:
00117   static const size_t DEFAULT_BUFFER_SIZE = 4;
00118   
00119   Camera(unsigned long guid, size_t bufferSize = DEFAULT_BUFFER_SIZE);
00120   Camera(const char* ip_address, size_t bufferSize = DEFAULT_BUFFER_SIZE);
00121 
00122   ~Camera();
00123 
00125   void setFrameCallback(boost::function<void (tPvFrame*)> callback);
00126   void setFrameRate(tPvFloat32 frame_rate);
00127 
00128   void setKillCallback(boost::function<void (unsigned long)> callback);
00130   void start(FrameStartTriggerMode = Freerun, tPvFloat32 frame_rate = 30, AcquisitionMode = Continuous);
00132   void stop();
00134   void removeEvents();
00137   tPvFrame* grab(unsigned long timeout_ms = PVINFINITE);
00138 
00139   void setExposure(unsigned int val, AutoSetting isauto = Manual);
00140   void setGain(unsigned int val, AutoSetting isauto = Manual);
00141   void setWhiteBalance(unsigned int blue, unsigned int red,
00142                        AutoSetting isauto = Manual);
00143 
00144   void setRoi(unsigned int x, unsigned int y,
00145               unsigned int width, unsigned int height);
00146   void setRoiToWholeFrame();
00147   void setBinning(unsigned int binning_x = 1, unsigned int binning_y = 1);
00148 
00150   bool hasAttribute(const std::string &name);
00151 
00153   void getAttributeEnum(const std::string &name, std::string &value);
00154   void getAttribute(const std::string &name, tPvUint32 &value);
00155   void getAttribute(const std::string &name, tPvFloat32 &value);
00156   void getAttribute(const std::string &name, std::string &value);
00157   
00158   void setAttributeEnum(const std::string &name, const std::string &value);
00159   void setAttribute(const std::string &name, tPvUint32 value);
00160   void setAttribute(const std::string &name, tPvFloat32 value);
00161   void setAttribute(const std::string &name, const std::string &value);
00162 
00163   void runCommand(const std::string& name);
00164   
00165   unsigned long guid();
00166 
00167   unsigned long getMaxDataRate();
00168   static const unsigned long GIGE_MAX_DATA_RATE = 115000000;
00169   
00171   static const size_t USER_MEMORY_SIZE = 512;
00172   void writeUserMemory(const char* data, size_t size);
00173   void readUserMemory(char* data, size_t size);
00174 
00176   tPvHandle handle();
00177   
00178 private:
00179   tPvHandle handle_; // handle to open camera
00180   tPvFrame* frames_; // array of frame buffers
00181   tPvUint32 frameSize_; // bytes per frame
00182   size_t bufferSize_; // number of frame buffers
00183   FrameStartTriggerMode FSTmode_;
00184   AcquisitionMode Amode_;
00185   boost::function<void (tPvFrame*)> userCallback_;
00186   boost::function<void (unsigned long UniqueId)> killCallback_;
00187   boost::mutex frameMutex_;
00188   boost::mutex aliveMutex_;
00189   size_t bufferIndex_;
00190 
00191   void setup();
00192   
00193   static void frameDone(tPvFrame* frame);
00194   static void kill(void* Context,
00195                     tPvInterface Interface,
00196                     tPvLinkEvent Event,
00197                     unsigned long UniqueId);
00198 };
00199 
00200 } // namespace prosilica
00201 
00202 #endif
00203 


prosilica_camera
Author(s): Maintained by William Woodall - wwoodall@willowgarage.com, Contributions by Allison Thackston - allison.thackston@nasa.gov
autogenerated on Thu Jun 6 2019 20:28:48