prosilica.cpp
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 #include "prosilica/prosilica.h"
00036 #include <prosilica_gige_sdk/PvRegIo.h>
00037 #include <cassert>
00038 #include <cstdio>
00039 #include <ctime>
00040 #include <cstring>
00041 #include <arpa/inet.h>
00042 
00043 #include <ros/console.h>
00044 
00045 #define CHECK_ERR(fnc, amsg)                               \
00046 do {                                                       \
00047   tPvErr err = fnc;                                        \
00048   if (err != ePvErrSuccess) {                              \
00049     char msg[256];                                         \
00050     snprintf(msg, 256, "%s: %s", amsg, errorStrings[err]); \
00051     throw ProsilicaException(err, msg);                    \
00052   }                                                        \
00053 } while (false)
00054 
00055 namespace prosilica {
00056 
00057 static const unsigned int MAX_CAMERA_LIST = 10;
00058 static const char* autoValues[] = {"Manual", "Auto", "AutoOnce"};
00059 static const char* triggerModes[] = {"Freerun", "SyncIn1", "SyncIn2", "FixedRate", "Software"};
00060 static const char* acquisitionModes[] = {"Continuous","SingleFrame","MultiFrame","Recorder"};
00061 static const char* errorStrings[] = {"No error",
00062                                      "Unexpected camera fault",
00063                                      "Unexpected fault in PvApi or driver",
00064                                      "Camera handle is invalid",
00065                                      "Bad parameter to API call",
00066                                      "Sequence of API calls is incorrect",
00067                                      "Camera or attribute not found",
00068                                      "Camera cannot be opened in the specified mode",
00069                                      "Camera was unplugged",
00070                                      "Setup is invalid (an attribute is invalid)",
00071                                      "System/network resources or memory not available",
00072                                      "1394 bandwidth not available",
00073                                      "Too many frames on queue",
00074                                      "Frame buffer is too small",
00075                                      "Frame cancelled by user",
00076                                      "The data for the frame was lost",
00077                                      "Some data in the frame is missing",
00078                                      "Timeout during wait",
00079                                      "Attribute value is out of the expected range",
00080                                      "Attribute is not this type (wrong access function)",
00081                                      "Attribute write forbidden at this time",
00082                                      "Attribute is not available at this time",
00083                                      "A firewall is blocking the traffic"};
00084 
00085 static tPvCameraInfo cameraList[MAX_CAMERA_LIST];
00086 static unsigned long cameraNum = 0;
00087 
00088 void init()
00089 {
00090   CHECK_ERR( PvInitialize(), "Failed to initialize Prosilica API" );
00091 }
00092 
00093 void fini()
00094 {
00095   PvUnInitialize();
00096 }
00097 
00098 size_t numCameras()
00099 {
00100   cameraNum = PvCameraList(cameraList, MAX_CAMERA_LIST, NULL);
00101   return cameraNum;
00102 }
00103 
00104 uint64_t getGuid(size_t i)
00105 {
00106   assert(i < MAX_CAMERA_LIST);
00107   if (i >= cameraNum)
00108     throw ProsilicaException(ePvErrBadParameter, "No camera at index i");
00109   return cameraList[i].UniqueId;
00110 }
00111 
00112 std::vector<CameraInfo> listCameras()
00113 {
00114     std::vector<CameraInfo> cameras;
00115     tPvCameraInfo cameraList[MAX_CAMERA_LIST];
00116     unsigned long cameraNum = 0;
00118     cameraNum = PvCameraList(cameraList, MAX_CAMERA_LIST, NULL);
00120     if (cameraNum < MAX_CAMERA_LIST)
00121     {
00122         cameraNum += PvCameraListUnreachable(&cameraList[cameraNum], MAX_CAMERA_LIST-cameraNum, NULL);
00123     }
00124     if(cameraNum)
00125     {
00126         struct in_addr addr;
00127         tPvIpSettings Conf;
00128 
00130         for(unsigned long i=0; i < cameraNum; i++)
00131         {
00132 
00133             CameraInfo camInfo;
00134             camInfo.serial     = to_string(cameraList[i].SerialString);
00135             camInfo.name       = to_string(cameraList[i].DisplayName);
00136             camInfo.guid       = to_string(cameraList[i].UniqueId);
00137             PvCameraIpSettingsGet(cameraList[i].UniqueId,&Conf);
00138             addr.s_addr = Conf.CurrentIpAddress;
00139             camInfo.ip_address = to_string(inet_ntoa(addr));
00140             camInfo.access     = cameraList[i].PermittedAccess & ePvAccessMaster ? true : false;
00141 
00142             cameras.push_back(camInfo);
00143         }
00144     }
00145     return cameras;
00146 }
00147 
00148 std::string getIPAddress(uint64_t guid)
00149 {
00150     struct in_addr addr;
00151     tPvIpSettings Conf;
00152     CHECK_ERR(PvCameraIpSettingsGet(guid, &Conf), "Unable to retrieve IP address");
00153     addr.s_addr = Conf.CurrentIpAddress;
00154     std::stringstream ip;
00155     ip<<inet_ntoa(addr);
00156     return ip.str();
00157 }
00158 
00160 static void openCamera(boost::function<tPvErr (tPvCameraInfo*)> info_fn,
00161                        boost::function<tPvErr (tPvAccessFlags)> open_fn)
00162 {
00163   cameraNum = PvCameraList(cameraList, MAX_CAMERA_LIST, NULL);
00164   tPvCameraInfo info;
00165   CHECK_ERR( info_fn(&info), "Unable to find requested camera" );
00166 
00167   if (!(info.PermittedAccess & ePvAccessMaster))
00168     throw ProsilicaException(ePvErrAccessDenied,
00169                              "Unable to open camera as master. "
00170                              "Another process is already using it.");
00171   
00172   CHECK_ERR( open_fn(ePvAccessMaster), "Unable to open requested camera" );
00173 }
00174 
00175 Camera::Camera(unsigned long guid, size_t bufferSize)
00176   : bufferSize_(bufferSize), FSTmode_(None)
00177 {
00178   openCamera(boost::bind(PvCameraInfo, guid, _1),
00179              boost::bind(PvCameraOpen, guid, _1, &handle_));
00180   
00181   setup();
00182 }
00183 
00184 Camera::Camera(const char* ip_address, size_t bufferSize)
00185   : bufferSize_(bufferSize), FSTmode_(None)
00186 {
00187   unsigned long addr = inet_addr(ip_address);
00188   tPvIpSettings settings;
00189   openCamera(boost::bind(PvCameraInfoByAddr, addr, _1, &settings),
00190              boost::bind(PvCameraOpenByAddr, addr, _1, &handle_));
00191   
00192   setup();
00193 }
00194 
00195 void Camera::setup()
00196 {
00197   // adjust packet size according to the current network capacity
00198   tPvUint32 maxPacketSize = 9000;
00199   PvCaptureAdjustPacketSize(handle_, maxPacketSize);
00200 
00201   // set data rate to the max
00202   unsigned long max_data_rate = getMaxDataRate();
00203   if (max_data_rate < GIGE_MAX_DATA_RATE) {
00204     ROS_WARN("Detected max data rate is %lu bytes/s, typical maximum data rate for a "
00205              "GigE port is %lu bytes/s. Are you using a GigE network card and cable?\n",
00206              max_data_rate, GIGE_MAX_DATA_RATE);
00207   }
00208   setAttribute("StreamBytesPerSecond", max_data_rate);
00209 
00210   // capture whole frame by default
00211   setBinning();
00212   setRoiToWholeFrame();
00213   
00214   // query for attributes (TODO: more)
00215   CHECK_ERR( PvAttrUint32Get(handle_, "TotalBytesPerFrame", &frameSize_),
00216              "Unable to retrieve frame size" );
00217   
00218   // allocate frame buffers
00219   frames_ = new tPvFrame[bufferSize_];
00220   memset(frames_, 0, sizeof(tPvFrame) * bufferSize_);
00221   for (unsigned int i = 0; i < bufferSize_; ++i)
00222   {
00223     frames_[i].ImageBuffer = new char[frameSize_];
00224     frames_[i].ImageBufferSize = frameSize_;
00225     frames_[i].Context[0] = (void*)this; // for frameDone callback
00226   }
00227 
00228   PvLinkCallbackRegister(Camera::kill, ePvLinkRemove, this);
00229 }
00230 
00231 Camera::~Camera()
00232 {
00233   PvLinkCallbackUnRegister(Camera::kill, ePvLinkRemove);
00234   stop();
00235   
00236   PvCameraClose(handle_);
00237 
00238   if (frames_)
00239   {
00240     for (unsigned int i = 0; i < bufferSize_; ++i)
00241       delete[] (char*)frames_[i].ImageBuffer;
00242     delete[] frames_;
00243   }
00244 }
00245 
00246 void Camera::setFrameCallback(boost::function<void (tPvFrame*)> callback)
00247 {
00248   userCallback_ = callback;
00249 }
00250 void Camera::setFrameRate(tPvFloat32 frame_rate){
00251   CHECK_ERR( PvAttrFloat32Set(handle_, "FrameRate", frame_rate),
00252              "Could not set frame rate");
00253 }
00254 
00255 void Camera::setKillCallback(boost::function<void (unsigned long UniqueId)> callback)
00256 {
00257     killCallback_ = callback;
00258 }
00259 
00260 void Camera::start(FrameStartTriggerMode fmode, tPvFloat32 frame_rate, AcquisitionMode amode)
00261 {
00262     assert( FSTmode_ == None && fmode != None );
00264     assert( fmode == SyncIn1 || fmode == SyncIn2 || fmode == Software || fmode == FixedRate || !userCallback_.empty() );
00265 
00266     // set camera in acquisition mode
00267     CHECK_ERR( PvCaptureStart(handle_), "Could not start capture");
00268 
00269     if (fmode == Freerun || fmode == FixedRate || fmode == SyncIn1 || fmode == SyncIn2)
00270     {
00271         for (unsigned int i = 0; i < bufferSize_; ++i)
00272             PvCaptureQueueFrame(handle_, frames_ + i, Camera::frameDone);
00273 
00274     }
00275     else
00276     {
00277         bufferIndex_ = 0;
00278         CHECK_ERR( PvCaptureQueueFrame(handle_, &frames_[bufferIndex_], NULL), "Could not queue frame");
00279     }
00280 
00281     // start capture after setting acquisition and trigger modes
00282     try {
00284         CHECK_ERR( PvAttrEnumSet(handle_, "AcquisitionMode", acquisitionModes[amode]),
00285                    "Could not set acquisition mode" );
00286         CHECK_ERR( PvAttrEnumSet(handle_, "FrameStartTriggerMode", triggerModes[fmode]),
00287                    "Could not set trigger mode" );
00288         CHECK_ERR( PvCommandRun(handle_, "AcquisitionStart"),
00289                    "Could not start acquisition" );
00290     }
00291     catch (ProsilicaException& e) {
00292         stop();
00293         throw; // rethrow
00294     }
00295     FSTmode_ = fmode;
00296     Amode_ = amode;
00297     
00298     CHECK_ERR( PvAttrFloat32Set(handle_, "FrameRate", frame_rate),
00299                    "Could not set frame rate");
00300 }
00301 
00302 void Camera::stop()
00303 {
00304   if (FSTmode_ == None)
00305     return;
00306   
00307   PvCommandRun(handle_, "AcquisitionStop");
00308   PvCaptureQueueClear(handle_);
00309   PvCaptureEnd(handle_);
00310   FSTmode_ = None;
00311 }
00312 
00313 void Camera::removeEvents()
00314 {
00315     // clear all events
00316     PvAttrUint32Set(handle_, "EventsEnable1", 0);
00317 }
00318 
00319 tPvFrame* Camera::grab(unsigned long timeout_ms)
00320 {
00321     assert( FSTmode_ == Software );
00322     tPvFrame* frame = &frames_[0];
00323 
00324     CHECK_ERR( PvCommandRun(handle_, "FrameStartTriggerSoftware"), "Couldn't trigger capture" );
00325     CHECK_ERR( PvCaptureWaitForFrameDone(handle_, frame, timeout_ms), "couldn't capture frame");
00326     // don't requeue if capture has stopped
00327     if (frame->Status == ePvErrUnplugged || frame->Status == ePvErrCancelled )
00328     {
00329       return NULL;
00330     }
00331     CHECK_ERR( PvCaptureQueueFrame(handle_, frame, NULL), "Couldn't queue frame");
00332 
00333     if (frame->Status == ePvErrSuccess)
00334         return frame;
00335     if (frame->Status == ePvErrDataMissing || frame->Status == ePvErrTimeout)
00336     {
00338         boost::this_thread::sleep(boost::posix_time::millisec(50));
00339         return NULL;
00340     }
00341     else
00342         throw std::runtime_error("Unknown error grabbing frame");
00343 
00344     return frame;
00345 }
00346 
00347 void Camera::setExposure(unsigned int val, AutoSetting isauto)
00348 {
00349   CHECK_ERR( PvAttrEnumSet(handle_, "ExposureMode", autoValues[isauto]),
00350              "Couldn't set exposure mode" );
00351 
00352   if (isauto == Manual)
00353     CHECK_ERR( PvAttrUint32Set(handle_, "ExposureValue", val),
00354                "Couldn't set exposure value" );
00355 }
00356 
00357 void Camera::setGain(unsigned int val, AutoSetting isauto)
00358 {
00361   if (PvAttrIsAvailable(handle_, "GainMode") == ePvErrSuccess)
00362   {
00363     CHECK_ERR( PvAttrEnumSet(handle_, "GainMode", autoValues[isauto]),
00364                "Couldn't set gain mode" );
00365   }
00366 
00367   if (isauto == Manual)
00368     CHECK_ERR( PvAttrUint32Set(handle_, "GainValue", val),
00369                "Couldn't set gain value" );
00370 }
00371 
00372 void Camera::setWhiteBalance(unsigned int blue, unsigned int red, AutoSetting isauto)
00373 {
00374   if (PvAttrIsAvailable(handle_, "WhitebalMode") == ePvErrSuccess)
00375   {
00376     CHECK_ERR( PvAttrEnumSet(handle_, "WhitebalMode", autoValues[isauto]),
00377                "Couldn't set white balance mode" );
00378   }
00379 
00380   if (isauto == Manual)
00381   {
00382       if(hasAttribute("WhitebalValueBlue"))
00383       {
00384         CHECK_ERR( PvAttrUint32Set(handle_, "WhitebalValueBlue", blue),
00385                    "Couldn't set white balance blue value" );
00386       }
00387       if(hasAttribute("WhitebalValueRed"))
00388       {
00389         CHECK_ERR( PvAttrUint32Set(handle_, "WhitebalValueRed", red),
00390                    "Couldn't set white balance red value" );
00391       }
00392   }
00393 }
00394 
00395 void Camera::setRoi(unsigned int x, unsigned int y,
00396                     unsigned int width, unsigned int height)
00397 {
00398   CHECK_ERR( PvAttrUint32Set(handle_, "RegionX", x),
00399              "Couldn't set region x (left edge)" );
00400   CHECK_ERR( PvAttrUint32Set(handle_, "RegionY", y),
00401              "Couldn't set region y (top edge)" );
00402   CHECK_ERR( PvAttrUint32Set(handle_, "Width", width),
00403              "Couldn't set region width" );
00404   CHECK_ERR( PvAttrUint32Set(handle_, "Height", height),
00405              "Couldn't set region height" );
00406 }
00407 
00408 void Camera::setRoiToWholeFrame()
00409 {
00410   tPvUint32 min_val, max_val;
00411   CHECK_ERR( PvAttrUint32Set(handle_, "RegionX", 0),
00412              "Couldn't set region x (left edge)" );
00413   CHECK_ERR( PvAttrUint32Set(handle_, "RegionY", 0),
00414              "Couldn't set region y (top edge)" );
00415   CHECK_ERR( PvAttrRangeUint32(handle_, "Width", &min_val, &max_val),
00416              "Couldn't get range of Width attribute" );
00417   CHECK_ERR( PvAttrUint32Set(handle_, "Width", max_val),
00418              "Couldn't set region width" );
00419   CHECK_ERR( PvAttrRangeUint32(handle_, "Height", &min_val, &max_val),
00420              "Couldn't get range of Height attribute" );
00421   CHECK_ERR( PvAttrUint32Set(handle_, "Height", max_val),
00422              "Couldn't set region height" );
00423 }
00424 
00425 void Camera::setBinning(unsigned int binning_x, unsigned int binning_y)
00426 {
00427   // Permit setting to "no binning" on cameras without binning support
00428   if (!hasAttribute("BinningX") && binning_x == 1 && binning_y == 1)
00429     return;
00430   
00431   CHECK_ERR( PvAttrUint32Set(handle_, "BinningX", binning_x),
00432              "Couldn't set horizontal binning" );
00433   CHECK_ERR( PvAttrUint32Set(handle_, "BinningY", binning_y),
00434              "Couldn't set vertical binning" );
00435 }
00436 
00437 bool Camera::hasAttribute(const std::string &name)
00438 {
00439   return (PvAttrIsAvailable(handle_, name.c_str()) == ePvErrSuccess);
00440 }
00441 
00442 static void getStringValuedAttribute(std::string &value,
00443   boost::function<tPvErr (char*, unsigned long, unsigned long*)> get_fn)
00444 {
00445   if (value.size() == 0)
00446     value.resize(32);
00447 
00448   unsigned long actual_size;
00449   CHECK_ERR( get_fn(&value[0], value.size(), &actual_size),
00450              "Couldn't get attribute" );
00451 
00452   if (actual_size >= value.size()) {
00453     value.resize(actual_size + 1);
00454     CHECK_ERR( get_fn(&value[0], value.size(), &actual_size),
00455                "Couldn't get attribute" );
00456   }
00457 }
00458 
00459 void Camera::getAttributeEnum(const std::string &name, std::string &value)
00460 {
00461   getStringValuedAttribute(value,
00462     boost::bind(PvAttrEnumGet, handle_, name.c_str(), _1, _2, _3));
00463 }
00464 
00465 void Camera::getAttribute(const std::string &name, tPvUint32 &value)
00466 {
00467   std::string err_msg = "Couldn't get attribute " + name;
00468   CHECK_ERR( PvAttrUint32Get(handle_, name.c_str(), &value),
00469              err_msg.c_str());
00470              
00471 }
00472 
00473 void Camera::getAttribute(const std::string &name, tPvFloat32 &value)
00474 {
00475 std::string err_msg = "Couldn't get attribute " + name;
00476   CHECK_ERR( PvAttrFloat32Get(handle_, name.c_str(), &value),
00477              err_msg.c_str());
00478 }
00479 
00480 void Camera::getAttribute(const std::string &name, std::string &value)
00481 {
00482   getStringValuedAttribute(value,
00483     boost::bind(PvAttrStringGet, handle_, name.c_str(), _1, _2, _3));
00484 }
00485 
00486 void Camera::setAttributeEnum(const std::string &name, const std::string &value)
00487 {
00488   std::string err_msg = "Couldn't get attribute " + name;
00489   CHECK_ERR( PvAttrEnumSet(handle_, name.c_str(), value.c_str()),
00490              err_msg.c_str());
00491 }
00492 
00493 void Camera::setAttribute(const std::string &name, tPvUint32 value)
00494 {
00495   std::string err_msg = "Couldn't set attribute " + name;
00496   CHECK_ERR( PvAttrUint32Set(handle_, name.c_str(), value),
00497              err_msg.c_str());
00498 }
00499 
00500 void Camera::setAttribute(const std::string &name, tPvFloat32 value)
00501 {
00502   std::string err_msg = "Couldn't set attribute " + name;
00503   CHECK_ERR( PvAttrFloat32Set(handle_, name.c_str(), value),
00504              err_msg.c_str());
00505 }
00506 
00507 void Camera::setAttribute(const std::string &name, const std::string &value)
00508 {
00509   std::string err_msg = "Couldn't set attribute " + name;
00510   CHECK_ERR( PvAttrStringSet(handle_, name.c_str(), value.c_str()),
00511              err_msg.c_str());
00512 }
00513 
00514 void Camera::runCommand(const std::string& name)
00515 {
00516   std::string err_msg = "Couldn't run command " + name;
00517   CHECK_ERR( PvCommandRun(handle_, name.c_str()), err_msg.c_str());
00518 }
00519 
00520 unsigned long Camera::guid()
00521 {
00522   unsigned long id;
00523   CHECK_ERR( PvAttrUint32Get(handle_, "UniqueId", &id),
00524              "Couldn't retrieve unique id" );
00525   return id;
00526 }
00527 
00528 unsigned long Camera::getMaxDataRate()
00529 {
00530   tPvUint32 min_data_rate, max_data_rate;
00531   CHECK_ERR( PvAttrRangeUint32(handle_, "StreamBytesPerSecond", &min_data_rate, &max_data_rate),
00532              "Couldn't get range of attribute StreamBytesPerSecond" );
00533   return max_data_rate;
00534 }
00535 
00536 static const unsigned long USER_ADDRESS = 0x17200;
00537 
00538 void Camera::writeUserMemory(const char* data, size_t size)
00539 {
00540   assert(size <= USER_MEMORY_SIZE);
00541 
00542   unsigned char buffer[USER_MEMORY_SIZE] = {0};
00543   memcpy(buffer, data, size);
00544 
00545   unsigned long written;
00546   CHECK_ERR( PvMemoryWrite(handle_, USER_ADDRESS, USER_MEMORY_SIZE, buffer, &written),
00547              "Couldn't write to user memory" );
00548 }
00549 
00550 void Camera::readUserMemory(char* data, size_t size)
00551 {
00552   assert(size <= USER_MEMORY_SIZE);
00553 
00554   unsigned char buffer[USER_MEMORY_SIZE];
00555   
00556   CHECK_ERR( PvMemoryRead(handle_, USER_ADDRESS, USER_MEMORY_SIZE, buffer),
00557              "Couldn't read from user memory" );
00558 
00559   memcpy(data, buffer, size);
00560 }
00561 
00562 void Camera::frameDone(tPvFrame* frame)
00563 {
00564 
00565   Camera* camPtr = (Camera*) frame->Context[0];
00566   if (camPtr && !camPtr->userCallback_.empty()) {
00567     // TODO: thread safety OK here?
00568     boost::lock_guard<boost::mutex> guard(camPtr->frameMutex_);
00569     camPtr->userCallback_(frame);
00570   }
00571 
00572   // don't requeue if capture has stopped
00573   if (frame->Status == ePvErrUnplugged || frame->Status == ePvErrCancelled)
00574   {
00575     return;
00576   }
00577   PvCaptureQueueFrame(camPtr->handle_, frame, Camera::frameDone);
00578 }
00579 
00580 
00581 void Camera::kill(void* Context,
00582                    tPvInterface Interface,
00583                    tPvLinkEvent Event,
00584                    unsigned long UniqueId)
00585 {
00586     Camera* camPtr = (Camera*) Context;
00587     if (camPtr && !camPtr->killCallback_.empty())
00588     {
00589         //boost::lock_guard<boost::mutex> guard(camPtr->aliveMutex_);
00590         camPtr->killCallback_(UniqueId);
00591     }
00592 }
00593 
00594 tPvHandle Camera::handle()
00595 {
00596   return handle_;
00597 }
00598 
00599 } // namespace prosilica
00600 


prosilica_camera
Author(s): Maintained by William Woodall - wwoodall@willowgarage.com, Contributions by Allison Thackston - allison.thackston@nasa.gov
autogenerated on Fri Aug 28 2015 12:15:29