prosilica.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef PROSILICA_H
36 #define PROSILICA_H
37 
38 #include <stdexcept>
39 #include <string>
40 #include <sstream>
41 #include <boost/function.hpp>
42 #include <boost/thread.hpp>
43 
44 // PvApi.h isn't aware of the usual detection macros
45 // these include support for i386, x86_64, and arm, on Linux and OSX
46 #define _LINUX
47 #define _x86
49 #undef _LINUX
50 #undef _x86
51 
52 
53 template <class T>
54 inline std::string to_string (const T& t)
55 {
56  std::stringstream ss;
57  ss << t;
58  return ss.str();
59 }
60 
61 namespace prosilica {
62 
63 struct ProsilicaException : public std::runtime_error
64 {
66 
67  ProsilicaException(tPvErr code, const char* msg)
68  : std::runtime_error(msg), error_code(code)
69  {}
70 };
71 struct CameraInfo
72 {
73  std::string serial;
74  std::string name;
75  std::string guid;
76  std::string ip_address;
77  bool access;
78 };
79 
80 void init(); // initializes API
81 void fini(); // releases internal resources
82 size_t numCameras(); // number of cameras found
83 uint64_t getGuid(size_t i); // camera ids
84 std::vector<CameraInfo> listCameras(); // get list of cameras available
85 std::string getIPAddress(uint64_t guid); //get ip address data from guid
86 
90 {
97 };
98 
100 {
105 };
106 
108 {
112 };
113 
114 class Camera
115 {
116 public:
117  static const size_t DEFAULT_BUFFER_SIZE = 4;
118 
119  Camera(unsigned long guid, size_t bufferSize = DEFAULT_BUFFER_SIZE);
120  Camera(const char* ip_address, size_t bufferSize = DEFAULT_BUFFER_SIZE);
121 
122  ~Camera();
123 
125  void setFrameCallback(boost::function<void (tPvFrame*)> callback);
126  void setFrameRate(tPvFloat32 frame_rate);
127 
128  void setKillCallback(boost::function<void (unsigned long)> callback);
130  void start(FrameStartTriggerMode = Freerun, tPvFloat32 frame_rate = 30, AcquisitionMode = Continuous);
132  void stop();
134  void removeEvents();
137  tPvFrame* grab(unsigned long timeout_ms = PVINFINITE);
138 
139  void setExposure(unsigned int val, AutoSetting isauto = Manual);
140  void setGain(unsigned int val, AutoSetting isauto = Manual);
141  void setWhiteBalance(unsigned int blue, unsigned int red,
142  AutoSetting isauto = Manual);
143 
144  void setRoi(unsigned int x, unsigned int y,
145  unsigned int width, unsigned int height);
146  void setRoiToWholeFrame();
147  void setBinning(unsigned int binning_x = 1, unsigned int binning_y = 1);
148 
150  bool hasAttribute(const std::string &name);
151 
153  void getAttributeEnum(const std::string &name, std::string &value);
154  void getAttribute(const std::string &name, tPvUint32 &value);
155  void getAttribute(const std::string &name, tPvFloat32 &value);
156  void getAttribute(const std::string &name, std::string &value);
157 
158  void setAttributeEnum(const std::string &name, const std::string &value);
159  void setAttribute(const std::string &name, tPvUint32 value);
160  void setAttribute(const std::string &name, tPvFloat32 value);
161  void setAttribute(const std::string &name, const std::string &value);
162 
163  void runCommand(const std::string& name);
164 
165  unsigned long guid();
166 
167  unsigned long getMaxDataRate();
168  static const unsigned long GIGE_MAX_DATA_RATE = 115000000;
169 
171  static const size_t USER_MEMORY_SIZE = 512;
172  void writeUserMemory(const char* data, size_t size);
173  void readUserMemory(char* data, size_t size);
174 
176  tPvHandle handle();
177 
178 private:
179  tPvHandle handle_; // handle to open camera
180  tPvFrame* frames_; // array of frame buffers
181  tPvUint32 frameSize_; // bytes per frame
182  size_t bufferSize_; // number of frame buffers
185  boost::function<void (tPvFrame*)> userCallback_;
186  boost::function<void (unsigned long UniqueId)> killCallback_;
187  boost::mutex frameMutex_;
188  boost::mutex aliveMutex_;
189  size_t bufferIndex_;
190 
191  void setup();
192 
193  static void frameDone(tPvFrame* frame);
194  static void kill(void* Context,
195  tPvInterface Interface,
196  tPvLinkEvent Event,
197  unsigned long UniqueId);
198 };
199 
200 } // namespace prosilica
201 
202 #endif
203 
tPvFrame * frames_
Definition: prosilica.h:180
AcquisitionMode
Definition: prosilica.h:99
std::string getIPAddress(uint64_t guid)
Definition: prosilica.cpp:148
void init()
Definition: prosilica.cpp:88
FrameStartTriggerMode FSTmode_
Definition: prosilica.h:183
uint64_t getGuid(size_t i)
Definition: prosilica.cpp:104
std::string serial
Definition: prosilica.h:73
tPvLinkEvent
tPvErr
std::vector< CameraInfo > listCameras()
Definition: prosilica.cpp:112
size_t numCameras()
Definition: prosilica.cpp:98
size_t bufferSize_
Definition: prosilica.h:182
void fini()
Definition: prosilica.cpp:93
std::string to_string(const T &t)
Definition: prosilica.h:54
AcquisitionMode Amode_
Definition: prosilica.h:184
size_t bufferIndex_
Definition: prosilica.h:189
void * tPvHandle
ProsilicaException(tPvErr code, const char *msg)
Definition: prosilica.h:67
std::string name
Definition: prosilica.h:74
FrameStartTriggerMode
Definition: prosilica.h:89
boost::mutex frameMutex_
Definition: prosilica.h:187
boost::function< void(tPvFrame *)> userCallback_
Definition: prosilica.h:185
tPvUint32 frameSize_
Definition: prosilica.h:181
std::string ip_address
Definition: prosilica.h:76
tPvHandle handle_
Definition: prosilica.h:179
tPvInterface
boost::mutex aliveMutex_
Definition: prosilica.h:188
std::string guid
Definition: prosilica.h:75
boost::function< void(unsigned long UniqueId)> killCallback_
Definition: prosilica.h:186


prosilica_camera
Author(s): Maintained by William Woodall - wwoodall@willowgarage.com, Contributions by Allison Thackston - allison.thackston@nasa.gov
autogenerated on Mon Jun 10 2019 14:20:19