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 <boost/function.hpp>
00041 #include <boost/thread.hpp>
00042
00043
00044
00045 #define _LINUX
00046 #define _x86
00047 #include <PvApi.h>
00048 #undef _LINUX
00049 #undef _x86
00050
00051 namespace prosilica {
00052
00053 struct ProsilicaException : public std::runtime_error
00054 {
00055 tPvErr error_code;
00056
00057 ProsilicaException(tPvErr code, const char* msg)
00058 : std::runtime_error(msg), error_code(code)
00059 {}
00060 };
00061
00062 void init();
00063 void fini();
00064 size_t numCameras();
00065 uint64_t getGuid(size_t i);
00066
00069 enum FrameStartTriggerMode
00070 {
00071 Freerun,
00072 SyncIn1,
00073 SyncIn2,
00074 FixedRate,
00075 Software,
00076 None
00077 };
00078
00079 enum AcquisitionMode
00080 {
00081 Continuous,
00082 SingleFrame,
00083 MultiFrame,
00084 Recorder
00085 };
00086
00087 enum AutoSetting
00088 {
00089 Manual,
00090 Auto,
00091 AutoOnce
00092 };
00093
00094 class Camera
00095 {
00096 public:
00097 static const size_t DEFAULT_BUFFER_SIZE = 4;
00098
00099 Camera(unsigned long guid, size_t bufferSize = DEFAULT_BUFFER_SIZE);
00100 Camera(const char* ip_address, size_t bufferSize = DEFAULT_BUFFER_SIZE);
00101
00102 ~Camera();
00103
00105 void setFrameCallback(boost::function<void (tPvFrame*)> callback);
00107 void start(FrameStartTriggerMode = Freerun, AcquisitionMode = Continuous);
00109 void stop();
00112 tPvFrame* grab(unsigned long timeout_ms = PVINFINITE);
00113
00114 void setExposure(unsigned int val, AutoSetting isauto = Manual);
00115 void setGain(unsigned int val, AutoSetting isauto = Manual);
00116 void setWhiteBalance(unsigned int blue, unsigned int red,
00117 AutoSetting isauto = Manual);
00118
00119 void setRoi(unsigned int x, unsigned int y,
00120 unsigned int width, unsigned int height);
00121 void setRoiToWholeFrame();
00122 void setBinning(unsigned int binning_x = 1, unsigned int binning_y = 1);
00123
00125 bool hasAttribute(const std::string &name);
00126
00128 void getAttributeEnum(const std::string &name, std::string &value);
00129 void getAttribute(const std::string &name, tPvUint32 &value);
00130 void getAttribute(const std::string &name, tPvFloat32 &value);
00131 void getAttribute(const std::string &name, std::string &value);
00132
00133 void setAttributeEnum(const std::string &name, const std::string &value);
00134 void setAttribute(const std::string &name, tPvUint32 value);
00135 void setAttribute(const std::string &name, tPvFloat32 value);
00136 void setAttribute(const std::string &name, const std::string &value);
00137
00138 void runCommand(const std::string& name);
00139
00140 unsigned long guid();
00141
00142 unsigned long getMaxDataRate();
00143 static const unsigned long GIGE_MAX_DATA_RATE = 115000000;
00144
00146 static const size_t USER_MEMORY_SIZE = 512;
00147 void writeUserMemory(const char* data, size_t size);
00148 void readUserMemory(char* data, size_t size);
00149
00151 tPvHandle handle();
00152
00153 private:
00154 tPvHandle handle_;
00155 tPvFrame* frames_;
00156 tPvUint32 frameSize_;
00157 size_t bufferSize_;
00158 FrameStartTriggerMode FSTmode_;
00159 AcquisitionMode Amode_;
00160 boost::function<void (tPvFrame*)> userCallback_;
00161 boost::mutex frameMutex_;
00162
00163 void setup();
00164
00165 static void frameDone(tPvFrame* frame);
00166 };
00167
00168 }
00169
00170 #endif