prosilica.cpp
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 #include "prosilica/prosilica.h"
37 #include <cassert>
38 #include <cstdio>
39 #include <ctime>
40 #include <cstring>
41 #include <arpa/inet.h>
42 
43 #include <ros/console.h>
44 
45 #define CHECK_ERR(fnc, amsg) \
46 do { \
47  tPvErr err = fnc; \
48  if (err != ePvErrSuccess) { \
49  char msg[256]; \
50  snprintf(msg, 256, "%s: %s", amsg, errorStrings[err]); \
51  throw ProsilicaException(err, msg); \
52  } \
53 } while (false)
54 
55 namespace prosilica {
56 
57 static const unsigned int MAX_CAMERA_LIST = 10;
58 static const char* autoValues[] = {"Manual", "Auto", "AutoOnce"};
59 static const char* triggerModes[] = {"Freerun", "SyncIn1", "SyncIn2", "FixedRate", "Software"};
60 static const char* acquisitionModes[] = {"Continuous","SingleFrame","MultiFrame","Recorder"};
61 static const char* errorStrings[] = {"No error",
62  "Unexpected camera fault",
63  "Unexpected fault in PvApi or driver",
64  "Camera handle is invalid",
65  "Bad parameter to API call",
66  "Sequence of API calls is incorrect",
67  "Camera or attribute not found",
68  "Camera cannot be opened in the specified mode",
69  "Camera was unplugged",
70  "Setup is invalid (an attribute is invalid)",
71  "System/network resources or memory not available",
72  "1394 bandwidth not available",
73  "Too many frames on queue",
74  "Frame buffer is too small",
75  "Frame cancelled by user",
76  "The data for the frame was lost",
77  "Some data in the frame is missing",
78  "Timeout during wait",
79  "Attribute value is out of the expected range",
80  "Attribute is not this type (wrong access function)",
81  "Attribute write forbidden at this time",
82  "Attribute is not available at this time",
83  "A firewall is blocking the traffic"};
84 
86 static unsigned long cameraNum = 0;
87 
88 void init()
89 {
90  CHECK_ERR( PvInitialize(), "Failed to initialize Prosilica API" );
91 }
92 
93 void fini()
94 {
96 }
97 
98 size_t numCameras()
99 {
100  cameraNum = PvCameraList(cameraList, MAX_CAMERA_LIST, NULL);
101  return cameraNum;
102 }
103 
104 uint64_t getGuid(size_t i)
105 {
106  assert(i < MAX_CAMERA_LIST);
107  if (i >= cameraNum)
108  throw ProsilicaException(ePvErrBadParameter, "No camera at index i");
109  return cameraList[i].UniqueId;
110 }
111 
112 std::vector<CameraInfo> listCameras()
113 {
114  std::vector<CameraInfo> cameras;
115  tPvCameraInfo cameraList[MAX_CAMERA_LIST];
116  unsigned long cameraNum = 0;
118  cameraNum = PvCameraList(cameraList, MAX_CAMERA_LIST, NULL);
120  if (cameraNum < MAX_CAMERA_LIST)
121  {
122  cameraNum += PvCameraListUnreachable(&cameraList[cameraNum], MAX_CAMERA_LIST-cameraNum, NULL);
123  }
124  if(cameraNum)
125  {
126  struct in_addr addr;
127  tPvIpSettings Conf;
128 
130  for(unsigned long i=0; i < cameraNum; i++)
131  {
132 
133  CameraInfo camInfo;
134  camInfo.serial = to_string(cameraList[i].SerialString);
135  camInfo.name = to_string(cameraList[i].DisplayName);
136  camInfo.guid = to_string(cameraList[i].UniqueId);
137  PvCameraIpSettingsGet(cameraList[i].UniqueId,&Conf);
138  addr.s_addr = Conf.CurrentIpAddress;
139  camInfo.ip_address = to_string(inet_ntoa(addr));
140  camInfo.access = cameraList[i].PermittedAccess & ePvAccessMaster ? true : false;
141 
142  cameras.push_back(camInfo);
143  }
144  }
145  return cameras;
146 }
147 
148 std::string getIPAddress(uint64_t guid)
149 {
150  struct in_addr addr;
151  tPvIpSettings Conf;
152  CHECK_ERR(PvCameraIpSettingsGet(guid, &Conf), "Unable to retrieve IP address");
153  addr.s_addr = Conf.CurrentIpAddress;
154  std::stringstream ip;
155  ip<<inet_ntoa(addr);
156  return ip.str();
157 }
158 
160 static void openCamera(boost::function<tPvErr (tPvCameraInfo*)> info_fn,
161  boost::function<tPvErr (tPvAccessFlags)> open_fn)
162 {
163  cameraNum = PvCameraList(cameraList, MAX_CAMERA_LIST, NULL);
164  tPvCameraInfo info;
165  CHECK_ERR( info_fn(&info), "Unable to find requested camera" );
166 
167  if (!(info.PermittedAccess & ePvAccessMaster))
169  "Unable to open camera as master. "
170  "Another process is already using it.");
171 
172  CHECK_ERR( open_fn(ePvAccessMaster), "Unable to open requested camera" );
173 }
174 
175 Camera::Camera(unsigned long guid, size_t bufferSize)
176  : bufferSize_(bufferSize), FSTmode_(None)
177 {
178  openCamera(boost::bind(PvCameraInfo, guid, _1),
179  boost::bind(PvCameraOpen, guid, _1, &handle_));
180 
181  setup();
182 }
183 
184 Camera::Camera(const char* ip_address, size_t bufferSize)
185  : bufferSize_(bufferSize), FSTmode_(None)
186 {
187  unsigned long addr = inet_addr(ip_address);
188  tPvIpSettings settings;
189  openCamera(boost::bind(PvCameraInfoByAddr, addr, _1, &settings),
190  boost::bind(PvCameraOpenByAddr, addr, _1, &handle_));
191 
192  setup();
193 }
194 
196 {
197  // adjust packet size according to the current network capacity
198  tPvUint32 maxPacketSize = 9000;
199  PvCaptureAdjustPacketSize(handle_, maxPacketSize);
200 
201  // set data rate to the max
202  unsigned long max_data_rate = getMaxDataRate();
203  if (max_data_rate < GIGE_MAX_DATA_RATE) {
204  ROS_WARN("Detected max data rate is %lu bytes/s, typical maximum data rate for a "
205  "GigE port is %lu bytes/s. Are you using a GigE network card and cable?\n",
206  max_data_rate, GIGE_MAX_DATA_RATE);
207  }
208  setAttribute("StreamBytesPerSecond", max_data_rate);
209 
210  // capture whole frame by default
211  setBinning();
213 
214  // query for attributes (TODO: more)
215  CHECK_ERR( PvAttrUint32Get(handle_, "TotalBytesPerFrame", &frameSize_),
216  "Unable to retrieve frame size" );
217 
218  // allocate frame buffers
220  memset(frames_, 0, sizeof(tPvFrame) * bufferSize_);
221  for (unsigned int i = 0; i < bufferSize_; ++i)
222  {
223  frames_[i].ImageBuffer = new char[frameSize_];
225  frames_[i].Context[0] = (void*)this; // for frameDone callback
226  }
227 
229 }
230 
232 {
234  stop();
235 
237 
238  if (frames_)
239  {
240  for (unsigned int i = 0; i < bufferSize_; ++i)
241  delete[] (char*)frames_[i].ImageBuffer;
242  delete[] frames_;
243  }
244 }
245 
246 void Camera::setFrameCallback(boost::function<void (tPvFrame*)> callback)
247 {
248  userCallback_ = callback;
249 }
250 void Camera::setFrameRate(tPvFloat32 frame_rate){
251  CHECK_ERR( PvAttrFloat32Set(handle_, "FrameRate", frame_rate),
252  "Could not set frame rate");
253 }
254 
255 void Camera::setKillCallback(boost::function<void (unsigned long UniqueId)> callback)
256 {
257  killCallback_ = callback;
258 }
259 
260 void Camera::start(FrameStartTriggerMode fmode, tPvFloat32 frame_rate, AcquisitionMode amode)
261 {
262  assert( FSTmode_ == None && fmode != None );
264  assert( fmode == SyncIn1 || fmode == SyncIn2 || fmode == Software || fmode == FixedRate || !userCallback_.empty() );
265 
266  // set camera in acquisition mode
267  CHECK_ERR( PvCaptureStart(handle_), "Could not start capture");
268 
269  if (fmode == Freerun || fmode == FixedRate || fmode == SyncIn1 || fmode == SyncIn2)
270  {
271  for (unsigned int i = 0; i < bufferSize_; ++i)
273 
274  }
275  else
276  {
277  bufferIndex_ = 0;
278  CHECK_ERR( PvCaptureQueueFrame(handle_, &frames_[bufferIndex_], NULL), "Could not queue frame");
279  }
280 
281  // start capture after setting acquisition and trigger modes
282  try {
284  CHECK_ERR( PvAttrEnumSet(handle_, "AcquisitionMode", acquisitionModes[amode]),
285  "Could not set acquisition mode" );
286  CHECK_ERR( PvAttrEnumSet(handle_, "FrameStartTriggerMode", triggerModes[fmode]),
287  "Could not set trigger mode" );
288  CHECK_ERR( PvCommandRun(handle_, "AcquisitionStart"),
289  "Could not start acquisition" );
290  }
291  catch (ProsilicaException& e) {
292  stop();
293  throw; // rethrow
294  }
295  FSTmode_ = fmode;
296  Amode_ = amode;
297 
298  CHECK_ERR( PvAttrFloat32Set(handle_, "FrameRate", frame_rate),
299  "Could not set frame rate");
300 }
301 
303 {
304  if (FSTmode_ == None)
305  return;
306 
307  PvCommandRun(handle_, "AcquisitionStop");
310  FSTmode_ = None;
311 }
312 
314 {
315  // clear all events
316  PvAttrUint32Set(handle_, "EventsEnable1", 0);
317 }
318 
319 tPvFrame* Camera::grab(unsigned long timeout_ms)
320 {
321  assert( FSTmode_ == Software );
322  tPvFrame* frame = &frames_[0];
323 
324  CHECK_ERR( PvCommandRun(handle_, "FrameStartTriggerSoftware"), "Couldn't trigger capture" );
325  CHECK_ERR( PvCaptureWaitForFrameDone(handle_, frame, timeout_ms), "couldn't capture frame");
326  // don't requeue if capture has stopped
327  if (frame->Status == ePvErrUnplugged || frame->Status == ePvErrCancelled )
328  {
329  return NULL;
330  }
331  CHECK_ERR( PvCaptureQueueFrame(handle_, frame, NULL), "Couldn't queue frame");
332 
333  if (frame->Status == ePvErrSuccess)
334  return frame;
335  if (frame->Status == ePvErrDataMissing || frame->Status == ePvErrTimeout)
336  {
338  boost::this_thread::sleep(boost::posix_time::millisec(50));
339  return NULL;
340  }
341  else
342  throw std::runtime_error("Unknown error grabbing frame");
343 
344  return frame;
345 }
346 
347 void Camera::setExposure(unsigned int val, AutoSetting isauto)
348 {
349  CHECK_ERR( PvAttrEnumSet(handle_, "ExposureMode", autoValues[isauto]),
350  "Couldn't set exposure mode" );
351 
352  if (isauto == Manual)
353  CHECK_ERR( PvAttrUint32Set(handle_, "ExposureValue", val),
354  "Couldn't set exposure value" );
355 }
356 
357 void Camera::setGain(unsigned int val, AutoSetting isauto)
358 {
361  if (PvAttrIsAvailable(handle_, "GainMode") == ePvErrSuccess)
362  {
363  CHECK_ERR( PvAttrEnumSet(handle_, "GainMode", autoValues[isauto]),
364  "Couldn't set gain mode" );
365  }
366 
367  if (isauto == Manual)
368  CHECK_ERR( PvAttrUint32Set(handle_, "GainValue", val),
369  "Couldn't set gain value" );
370 }
371 
372 void Camera::setWhiteBalance(unsigned int blue, unsigned int red, AutoSetting isauto)
373 {
374  if (PvAttrIsAvailable(handle_, "WhitebalMode") == ePvErrSuccess)
375  {
376  CHECK_ERR( PvAttrEnumSet(handle_, "WhitebalMode", autoValues[isauto]),
377  "Couldn't set white balance mode" );
378  }
379 
380  if (isauto == Manual)
381  {
382  if(hasAttribute("WhitebalValueBlue"))
383  {
384  CHECK_ERR( PvAttrUint32Set(handle_, "WhitebalValueBlue", blue),
385  "Couldn't set white balance blue value" );
386  }
387  if(hasAttribute("WhitebalValueRed"))
388  {
389  CHECK_ERR( PvAttrUint32Set(handle_, "WhitebalValueRed", red),
390  "Couldn't set white balance red value" );
391  }
392  }
393 }
394 
395 void Camera::setRoi(unsigned int x, unsigned int y,
396  unsigned int width, unsigned int height)
397 {
398  CHECK_ERR( PvAttrUint32Set(handle_, "RegionX", x),
399  "Couldn't set region x (left edge)" );
400  CHECK_ERR( PvAttrUint32Set(handle_, "RegionY", y),
401  "Couldn't set region y (top edge)" );
402  CHECK_ERR( PvAttrUint32Set(handle_, "Width", width),
403  "Couldn't set region width" );
404  CHECK_ERR( PvAttrUint32Set(handle_, "Height", height),
405  "Couldn't set region height" );
406 }
407 
409 {
410  tPvUint32 min_val, max_val;
411  CHECK_ERR( PvAttrUint32Set(handle_, "RegionX", 0),
412  "Couldn't set region x (left edge)" );
413  CHECK_ERR( PvAttrUint32Set(handle_, "RegionY", 0),
414  "Couldn't set region y (top edge)" );
415  CHECK_ERR( PvAttrRangeUint32(handle_, "Width", &min_val, &max_val),
416  "Couldn't get range of Width attribute" );
417  CHECK_ERR( PvAttrUint32Set(handle_, "Width", max_val),
418  "Couldn't set region width" );
419  CHECK_ERR( PvAttrRangeUint32(handle_, "Height", &min_val, &max_val),
420  "Couldn't get range of Height attribute" );
421  CHECK_ERR( PvAttrUint32Set(handle_, "Height", max_val),
422  "Couldn't set region height" );
423 }
424 
425 void Camera::setBinning(unsigned int binning_x, unsigned int binning_y)
426 {
427  // Permit setting to "no binning" on cameras without binning support
428  if (!hasAttribute("BinningX") && binning_x == 1 && binning_y == 1)
429  return;
430 
431  CHECK_ERR( PvAttrUint32Set(handle_, "BinningX", binning_x),
432  "Couldn't set horizontal binning" );
433  CHECK_ERR( PvAttrUint32Set(handle_, "BinningY", binning_y),
434  "Couldn't set vertical binning" );
435 }
436 
437 bool Camera::hasAttribute(const std::string &name)
438 {
439  return (PvAttrIsAvailable(handle_, name.c_str()) == ePvErrSuccess);
440 }
441 
442 static void getStringValuedAttribute(std::string &value,
443  boost::function<tPvErr (char*, unsigned long, unsigned long*)> get_fn)
444 {
445  if (value.size() == 0)
446  value.resize(32);
447 
448  unsigned long actual_size;
449  CHECK_ERR( get_fn(&value[0], value.size(), &actual_size),
450  "Couldn't get attribute" );
451 
452  if (actual_size >= value.size()) {
453  value.resize(actual_size + 1);
454  CHECK_ERR( get_fn(&value[0], value.size(), &actual_size),
455  "Couldn't get attribute" );
456  }
457 }
458 
459 void Camera::getAttributeEnum(const std::string &name, std::string &value)
460 {
462  boost::bind(PvAttrEnumGet, handle_, name.c_str(), _1, _2, _3));
463 }
464 
465 void Camera::getAttribute(const std::string &name, tPvUint32 &value)
466 {
467  std::string err_msg = "Couldn't get attribute " + name;
468  CHECK_ERR( PvAttrUint32Get(handle_, name.c_str(), &value),
469  err_msg.c_str());
470 
471 }
472 
473 void Camera::getAttribute(const std::string &name, tPvFloat32 &value)
474 {
475 std::string err_msg = "Couldn't get attribute " + name;
476  CHECK_ERR( PvAttrFloat32Get(handle_, name.c_str(), &value),
477  err_msg.c_str());
478 }
479 
480 void Camera::getAttribute(const std::string &name, std::string &value)
481 {
483  boost::bind(PvAttrStringGet, handle_, name.c_str(), _1, _2, _3));
484 }
485 
486 void Camera::setAttributeEnum(const std::string &name, const std::string &value)
487 {
488  std::string err_msg = "Couldn't get attribute " + name;
489  CHECK_ERR( PvAttrEnumSet(handle_, name.c_str(), value.c_str()),
490  err_msg.c_str());
491 }
492 
493 void Camera::setAttribute(const std::string &name, tPvUint32 value)
494 {
495  std::string err_msg = "Couldn't set attribute " + name;
496  CHECK_ERR( PvAttrUint32Set(handle_, name.c_str(), value),
497  err_msg.c_str());
498 }
499 
500 void Camera::setAttribute(const std::string &name, tPvFloat32 value)
501 {
502  std::string err_msg = "Couldn't set attribute " + name;
503  CHECK_ERR( PvAttrFloat32Set(handle_, name.c_str(), value),
504  err_msg.c_str());
505 }
506 
507 void Camera::setAttribute(const std::string &name, const std::string &value)
508 {
509  std::string err_msg = "Couldn't set attribute " + name;
510  CHECK_ERR( PvAttrStringSet(handle_, name.c_str(), value.c_str()),
511  err_msg.c_str());
512 }
513 
514 void Camera::runCommand(const std::string& name)
515 {
516  std::string err_msg = "Couldn't run command " + name;
517  CHECK_ERR( PvCommandRun(handle_, name.c_str()), err_msg.c_str());
518 }
519 
520 unsigned long Camera::guid()
521 {
522  unsigned long id;
523  CHECK_ERR( PvAttrUint32Get(handle_, "UniqueId", &id),
524  "Couldn't retrieve unique id" );
525  return id;
526 }
527 
528 unsigned long Camera::getMaxDataRate()
529 {
530  tPvUint32 min_data_rate, max_data_rate;
531  CHECK_ERR( PvAttrRangeUint32(handle_, "StreamBytesPerSecond", &min_data_rate, &max_data_rate),
532  "Couldn't get range of attribute StreamBytesPerSecond" );
533  return max_data_rate;
534 }
535 
536 static const unsigned long USER_ADDRESS = 0x17200;
537 
538 void Camera::writeUserMemory(const char* data, size_t size)
539 {
540  assert(size <= USER_MEMORY_SIZE);
541 
542  unsigned char buffer[USER_MEMORY_SIZE] = {0};
543  memcpy(buffer, data, size);
544 
545  unsigned long written;
546  CHECK_ERR( PvMemoryWrite(handle_, USER_ADDRESS, USER_MEMORY_SIZE, buffer, &written),
547  "Couldn't write to user memory" );
548 }
549 
550 void Camera::readUserMemory(char* data, size_t size)
551 {
552  assert(size <= USER_MEMORY_SIZE);
553 
554  unsigned char buffer[USER_MEMORY_SIZE];
555 
556  CHECK_ERR( PvMemoryRead(handle_, USER_ADDRESS, USER_MEMORY_SIZE, buffer),
557  "Couldn't read from user memory" );
558 
559  memcpy(data, buffer, size);
560 }
561 
563 {
564 
565  Camera* camPtr = (Camera*) frame->Context[0];
566  if (camPtr && !camPtr->userCallback_.empty()) {
567  // TODO: thread safety OK here?
568  boost::lock_guard<boost::mutex> guard(camPtr->frameMutex_);
569  camPtr->userCallback_(frame);
570  }
571 
572  // don't requeue if capture has stopped
573  if (frame->Status == ePvErrUnplugged || frame->Status == ePvErrCancelled)
574  {
575  return;
576  }
578 }
579 
580 
581 void Camera::kill(void* Context,
582  tPvInterface Interface,
583  tPvLinkEvent Event,
584  unsigned long UniqueId)
585 {
586  Camera* camPtr = (Camera*) Context;
587  if (camPtr && !camPtr->killCallback_.empty())
588  {
589  //boost::lock_guard<boost::mutex> guard(camPtr->aliveMutex_);
590  camPtr->killCallback_(UniqueId);
591  }
592 }
593 
595 {
596  return handle_;
597 }
598 
599 } // namespace prosilica
600 
tPvErr Status
void getAttributeEnum(const std::string &name, std::string &value)
General get/set attribute functions.
Definition: prosilica.cpp:459
tPvErr PVDECL PvCaptureQueueFrame(tPvHandle Camera, tPvFrame *pFrame, tPvFrameCallback Callback)
tPvErr PVDECL PvCameraOpen(unsigned long UniqueId, tPvAccessFlags AccessFlag, tPvHandle *pCamera)
unsigned long PermittedAccess
static unsigned long cameraNum
Definition: prosilica.cpp:86
tPvFrame * frames_
Definition: prosilica.h:180
ePvErrBadParameter
void readUserMemory(char *data, size_t size)
Definition: prosilica.cpp:550
tPvErr PVDECL PvAttrRangeUint32(tPvHandle Camera, const char *Name, tPvUint32 *pMin, tPvUint32 *pMax)
void setRoiToWholeFrame()
Definition: prosilica.cpp:408
tPvErr PVDECL PvCaptureStart(tPvHandle Camera)
void setExposure(unsigned int val, AutoSetting isauto=Manual)
Definition: prosilica.cpp:347
unsigned long UniqueId
ePvErrAccessDenied
unsigned long PVDECL PvCameraList(tPvCameraInfo *pList, unsigned long ListLength, unsigned long *pConnectedNum)
AcquisitionMode
Definition: prosilica.h:99
void setRoi(unsigned int x, unsigned int y, unsigned int width, unsigned int height)
Definition: prosilica.cpp:395
std::string getIPAddress(uint64_t guid)
Definition: prosilica.cpp:148
tPvErr PVDECL PvAttrFloat32Get(tPvHandle Camera, const char *Name, tPvFloat32 *pValue)
tPvErr PVDECL PvCaptureAdjustPacketSize(tPvHandle Camera, unsigned long MaximumPacketSize)
tPvErr PVDECL PvCaptureWaitForFrameDone(tPvHandle Camera, const tPvFrame *pFrame, unsigned long Timeout)
Camera(unsigned long guid, size_t bufferSize=DEFAULT_BUFFER_SIZE)
Definition: prosilica.cpp:175
tPvErr PVDECL PvAttrStringGet(tPvHandle Camera, const char *Name, char *pBuffer, unsigned long BufferSize, unsigned long *pSize)
void init()
Definition: prosilica.cpp:88
FrameStartTriggerMode FSTmode_
Definition: prosilica.h:183
tPvFrame * grab(unsigned long timeout_ms=PVINFINITE)
Definition: prosilica.cpp:319
uint64_t getGuid(size_t i)
Definition: prosilica.cpp:104
tPvErr PVDECL PvAttrFloat32Set(tPvHandle Camera, const char *Name, tPvFloat32 Value)
std::string serial
Definition: prosilica.h:73
tPvErr PVDECL PvCaptureQueueClear(tPvHandle Camera)
ePvErrUnplugged
static tPvCameraInfo cameraList[MAX_CAMERA_LIST]
Definition: prosilica.cpp:85
void setAttribute(const std::string &name, tPvUint32 value)
Definition: prosilica.cpp:493
ePvErrSuccess
static const char * errorStrings[]
Definition: prosilica.cpp:61
#define ROS_WARN(...)
tPvLinkEvent
tPvErr
void runCommand(const std::string &name)
Definition: prosilica.cpp:514
ePvErrCancelled
unsigned long getMaxDataRate()
Definition: prosilica.cpp:528
static const size_t USER_MEMORY_SIZE
Data must have size <= USER_MEMORY_SIZE bytes.
Definition: prosilica.h:171
static const char * autoValues[]
Definition: prosilica.cpp:58
tPvErr PVDECL PvAttrUint32Get(tPvHandle Camera, const char *Name, tPvUint32 *pValue)
std::vector< CameraInfo > listCameras()
Definition: prosilica.cpp:112
static const unsigned int MAX_CAMERA_LIST
Definition: prosilica.cpp:57
size_t numCameras()
Definition: prosilica.cpp:98
#define CHECK_ERR(fnc, amsg)
Definition: prosilica.cpp:45
static const unsigned long GIGE_MAX_DATA_RATE
Definition: prosilica.h:168
tPvErr PVDECL PvLinkCallbackUnRegister(tPvLinkCallback Callback, tPvLinkEvent Event)
tPvErr PVDECL PvCommandRun(tPvHandle Camera, const char *Name)
void setKillCallback(boost::function< void(unsigned long)> callback)
Definition: prosilica.cpp:255
static void getStringValuedAttribute(std::string &value, boost::function< tPvErr(char *, unsigned long, unsigned long *)> get_fn)
Definition: prosilica.cpp:442
ePvErrTimeout
tPvErr PVDECL PvAttrStringSet(tPvHandle Camera, const char *Name, const char *Value)
static const char * triggerModes[]
Definition: prosilica.cpp:59
static void openCamera(boost::function< tPvErr(tPvCameraInfo *)> info_fn, boost::function< tPvErr(tPvAccessFlags)> open_fn)
Definition: prosilica.cpp:160
unsigned long PVDECL PvCameraListUnreachable(tPvCameraInfo *pList, unsigned long ListLength, unsigned long *pConnectedNum)
size_t bufferSize_
Definition: prosilica.h:182
void stop()
Stop capture.
Definition: prosilica.cpp:302
void fini()
Definition: prosilica.cpp:93
std::string to_string(const T &t)
Definition: prosilica.h:54
void setGain(unsigned int val, AutoSetting isauto=Manual)
Definition: prosilica.cpp:357
void removeEvents()
remove callback
Definition: prosilica.cpp:313
unsigned long guid()
Definition: prosilica.cpp:520
ePvErrDataMissing
AcquisitionMode Amode_
Definition: prosilica.h:184
#define PvMemoryRead
tPvHandle handle()
Get raw PvApi camera handle.
Definition: prosilica.cpp:594
tPvErr PVDECL PvAttrEnumSet(tPvHandle Camera, const char *Name, const char *Value)
void setAttributeEnum(const std::string &name, const std::string &value)
Definition: prosilica.cpp:486
tPvErr PVDECL PvCameraOpenByAddr(unsigned long IpAddr, tPvAccessFlags AccessFlag, tPvHandle *pCamera)
size_t bufferIndex_
Definition: prosilica.h:189
void * tPvHandle
tPvErr PVDECL PvCaptureEnd(tPvHandle Camera)
void * ImageBuffer
std::string name
Definition: prosilica.h:74
bool hasAttribute(const std::string &name)
Returns true if camera supports the attribute.
Definition: prosilica.cpp:437
tPvErr PVDECL PvInitialize(void)
FrameStartTriggerMode
Definition: prosilica.h:89
void setFrameRate(tPvFloat32 frame_rate)
Definition: prosilica.cpp:250
boost::mutex frameMutex_
Definition: prosilica.h:187
void * Context[4]
tPvAccessFlags
boost::function< void(tPvFrame *)> userCallback_
Definition: prosilica.h:185
void setFrameCallback(boost::function< void(tPvFrame *)> callback)
Must be used before calling start() in a non-triggered mode.
Definition: prosilica.cpp:246
tPvErr PVDECL PvLinkCallbackRegister(tPvLinkCallback Callback, tPvLinkEvent Event, void *Context)
tPvUint32 frameSize_
Definition: prosilica.h:181
tPvErr PVDECL PvAttrUint32Set(tPvHandle Camera, const char *Name, tPvUint32 Value)
static void kill(void *Context, tPvInterface Interface, tPvLinkEvent Event, unsigned long UniqueId)
Definition: prosilica.cpp:581
void getAttribute(const std::string &name, tPvUint32 &value)
Definition: prosilica.cpp:465
tPvErr PVDECL PvAttrIsAvailable(tPvHandle Camera, const char *Name)
std::string ip_address
Definition: prosilica.h:76
void writeUserMemory(const char *data, size_t size)
Definition: prosilica.cpp:538
void setBinning(unsigned int binning_x=1, unsigned int binning_y=1)
Definition: prosilica.cpp:425
void start(FrameStartTriggerMode=Freerun, tPvFloat32 frame_rate=30, AcquisitionMode=Continuous)
Start capture.
Definition: prosilica.cpp:260
void setWhiteBalance(unsigned int blue, unsigned int red, AutoSetting isauto=Manual)
Definition: prosilica.cpp:372
tPvHandle handle_
Definition: prosilica.h:179
unsigned long ImageBufferSize
tPvInterface
ePvLinkRemove
static const char * acquisitionModes[]
Definition: prosilica.cpp:60
static const unsigned long USER_ADDRESS
Definition: prosilica.cpp:536
ePvAccessMaster
void PVDECL PvUnInitialize(void)
tPvErr PVDECL PvCameraInfo(unsigned long UniqueId, tPvCameraInfo *pInfo)
std::string guid
Definition: prosilica.h:75
tPvErr PVDECL PvCameraClose(tPvHandle Camera)
tPvErr PVDECL PvCameraIpSettingsGet(unsigned long UniqueId, tPvIpSettings *pSettings)
tPvErr PVDECL PvAttrEnumGet(tPvHandle Camera, const char *Name, char *pBuffer, unsigned long BufferSize, unsigned long *pSize)
tPvErr PVDECL PvCameraInfoByAddr(unsigned long IpAddr, tPvCameraInfo *pInfo, tPvIpSettings *pIpSettings)
boost::function< void(unsigned long UniqueId)> killCallback_
Definition: prosilica.h:186
static void frameDone(tPvFrame *frame)
Definition: prosilica.cpp:562
#define PvMemoryWrite


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