Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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
00045
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();
00081 void fini();
00082 size_t numCameras();
00083 uint64_t getGuid(size_t i);
00084 std::vector<CameraInfo> listCameras();
00085 std::string getIPAddress(uint64_t 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_;
00180 tPvFrame* frames_;
00181 tPvUint32 frameSize_;
00182 size_t bufferSize_;
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 }
00201
00202 #endif
00203