device.cc
Go to the documentation of this file.
00001 /*
00002  * This file is part of the rc_genicam_api package.
00003  *
00004  * Copyright (c) 2017 Roboception GmbH
00005  * All rights reserved
00006  *
00007  * Author: Heiko Hirschmueller
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions are met:
00011  *
00012  * 1. Redistributions of source code must retain the above copyright notice,
00013  * this list of conditions and the following disclaimer.
00014  *
00015  * 2. Redistributions in binary form must reproduce the above copyright notice,
00016  * this list of conditions and the following disclaimer in the documentation
00017  * and/or other materials provided with the distribution.
00018  *
00019  * 3. Neither the name of the copyright holder nor the names of its contributors
00020  * may be used to endorse or promote products derived from this software without
00021  * specific prior written permission.
00022  *
00023  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00024  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00025  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00026  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
00027  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00028  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00029  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00030  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00031  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00032  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  * POSSIBILITY OF SUCH DAMAGE.
00034  */
00035 
00036 #include "device.h"
00037 #include "stream.h"
00038 
00039 #include "gentl_wrapper.h"
00040 #include "exception.h"
00041 #include "cport.h"
00042 
00043 #include <iostream>
00044 
00045 namespace rcg
00046 {
00047 
00048 Device::Device(const std::shared_ptr<Interface> &_parent,
00049                const std::shared_ptr<const GenTLWrapper> &_gentl, const char *_id)
00050 {
00051   parent=_parent;
00052   gentl=_gentl;
00053   id=_id;
00054 
00055   n_open=0;
00056   dev=0;
00057   rp=0;
00058 }
00059 
00060 Device::~Device()
00061 {
00062   if (n_open > 0)
00063   {
00064     try
00065     {
00066       gentl->DevClose(dev);
00067     }
00068     catch (...) // do not throw exceptions in destructor
00069     { }
00070 
00071     parent->close();
00072   }
00073 }
00074 
00075 std::shared_ptr<Interface> Device::getParent() const
00076 {
00077   return parent;
00078 }
00079 
00080 const std::string &Device::getID() const
00081 {
00082   return id;
00083 }
00084 
00085 void Device::open(ACCESS access)
00086 {
00087   std::lock_guard<std::mutex> lock(mtx);
00088 
00089   if (n_open == 0)
00090   {
00091     parent->open();
00092 
00093     // convert access mode to GenTL flags
00094 
00095     GenTL::DEVICE_ACCESS_FLAGS mode[]={GenTL::DEVICE_ACCESS_READONLY,
00096       GenTL::DEVICE_ACCESS_CONTROL, GenTL::DEVICE_ACCESS_EXCLUSIVE};
00097 
00098     int i=0;
00099     switch (access)
00100     {
00101       case READONLY:
00102         i=0;
00103         break;
00104 
00105       case CONTROL:
00106         i=1;
00107         break;
00108 
00109       default:
00110       case EXCLUSIVE:
00111         i=2;
00112         break;
00113     }
00114 
00115     // open device (if readonly fails, try control; if control fails try
00116     // exclusive)
00117 
00118     GenTL::GC_ERROR err = GenTL::GC_ERR_NOT_IMPLEMENTED;
00119     while (err == GenTL::GC_ERR_NOT_IMPLEMENTED && i < 3)
00120     {
00121       err=gentl->IFOpenDevice(parent->getHandle(), id.c_str(), mode[i], &dev);
00122       i++;
00123     }
00124 
00125     // check if open was successful
00126 
00127     if (err != GenTL::GC_ERR_SUCCESS)
00128     {
00129       parent->close();
00130       throw GenTLException("Device::open() failed", gentl);
00131     }
00132   }
00133 
00134   n_open++;
00135 }
00136 
00137 void Device::close()
00138 {
00139   std::lock_guard<std::mutex> lock(mtx);
00140 
00141   if (n_open > 0)
00142   {
00143     n_open--;
00144   }
00145 
00146   if (n_open == 0)
00147   {
00148     gentl->DevClose(dev);
00149     dev=0;
00150     rp=0;
00151 
00152     nodemap=0;
00153     rnodemap=0;
00154 
00155     cport=0;
00156     rport=0;
00157 
00158     parent->close();
00159   }
00160 }
00161 
00162 namespace
00163 {
00164 
00165 int find(const std::vector<std::shared_ptr<Stream> > &list, const std::string &id)
00166 {
00167   for (size_t i=0; i<list.size(); i++)
00168   {
00169     if (list[i]->getID() == id)
00170     {
00171       return static_cast<int>(i);
00172     }
00173   }
00174 
00175   return -1;
00176 }
00177 
00178 }
00179 
00180 std::vector<std::shared_ptr<Stream> > Device::getStreams()
00181 {
00182   std::lock_guard<std::mutex> lock(mtx);
00183 
00184   std::vector<std::shared_ptr<Stream> > ret;
00185 
00186   if (dev != 0)
00187   {
00188     // get list of previously requested devices that are still in use
00189 
00190     std::vector<std::shared_ptr<Stream> > current;
00191 
00192     for (size_t i=0; i<slist.size(); i++)
00193     {
00194       std::shared_ptr<Stream> p=slist[i].lock();
00195       if (p)
00196       {
00197         current.push_back(p);
00198       }
00199     }
00200 
00201     // create list of interfaces, using either existing interfaces or
00202     // instantiating new ones
00203 
00204     uint32_t n=0;
00205     if (gentl->DevGetNumDataStreams(dev, &n) != GenTL::GC_ERR_SUCCESS)
00206     {
00207       throw GenTLException("Device::getStreams()", gentl);
00208     }
00209 
00210     for (uint32_t i=0; i<n; i++)
00211     {
00212       char tmp[256]="";
00213       size_t size=sizeof(tmp);
00214 
00215       if (gentl->DevGetDataStreamID(dev, i, tmp, &size) != GenTL::GC_ERR_SUCCESS)
00216       {
00217         throw GenTLException("Device::getStreams()", gentl);
00218       }
00219 
00220       int k=find(current, tmp);
00221 
00222       if (k >= 0)
00223       {
00224         ret.push_back(current[static_cast<size_t>(k)]);
00225       }
00226       else
00227       {
00228         ret.push_back(std::shared_ptr<Stream>(new Stream(shared_from_this(), gentl, tmp)));
00229       }
00230     }
00231 
00232     // update internal list of devices for reusage on next call
00233 
00234     slist.clear();
00235     for (size_t i=0; i<ret.size(); i++)
00236     {
00237       slist.push_back(ret[i]);
00238     }
00239   }
00240 
00241   return ret;
00242 
00243 }
00244 
00245 namespace
00246 {
00247 
00248 std::string cDevGetInfo(const Device *obj, const std::shared_ptr<const GenTLWrapper> &gentl,
00249                         GenTL::DEVICE_INFO_CMD info)
00250 {
00251   std::string ret;
00252 
00253   GenTL::INFO_DATATYPE type=GenTL::INFO_DATATYPE_UNKNOWN;
00254   char tmp[1024]="";
00255   size_t tmp_size=sizeof(tmp);
00256   GenTL::GC_ERROR err=GenTL::GC_ERR_ERROR;
00257 
00258   if (obj->getHandle() != 0)
00259   {
00260     err=gentl->DevGetInfo(obj->getHandle(), info, &type, tmp, &tmp_size);
00261   }
00262   else if (obj->getParent()->getHandle() != 0)
00263   {
00264     err=gentl->IFGetDeviceInfo(obj->getParent()->getHandle(), obj->getID().c_str(), info, &type,
00265                                tmp, &tmp_size);
00266   }
00267 
00268   if (err == GenTL::GC_ERR_SUCCESS && type == GenTL::INFO_DATATYPE_STRING)
00269   {
00270     for (size_t i=0; i<tmp_size && tmp[i] != '\0'; i++)
00271     {
00272       ret.push_back(tmp[i]);
00273     }
00274   }
00275 
00276   return ret;
00277 }
00278 
00279 }
00280 
00281 std::string Device::getVendor()
00282 {
00283   std::lock_guard<std::mutex> lock(mtx);
00284   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_VENDOR);
00285 }
00286 
00287 std::string Device::getModel()
00288 {
00289   std::lock_guard<std::mutex> lock(mtx);
00290   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_MODEL);
00291 }
00292 
00293 std::string Device::getTLType()
00294 {
00295   std::lock_guard<std::mutex> lock(mtx);
00296   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_TLTYPE);
00297 }
00298 
00299 std::string Device::getDisplayName()
00300 {
00301   std::lock_guard<std::mutex> lock(mtx);
00302   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_DISPLAYNAME);
00303 }
00304 
00305 std::string Device::getAccessStatus()
00306 {
00307   std::lock_guard<std::mutex> lock(mtx);
00308   std::string ret;
00309 
00310   GenTL::INFO_DATATYPE type=GenTL::INFO_DATATYPE_UNKNOWN;
00311   int32_t status=-1;
00312   size_t size=sizeof(status);
00313   GenTL::GC_ERROR err=GenTL::GC_ERR_ERROR;
00314 
00315   if (dev != 0)
00316   {
00317     err=gentl->DevGetInfo(dev, GenTL::DEVICE_INFO_ACCESS_STATUS, &type, &status, &size);
00318   }
00319   else if (parent->getHandle() != 0)
00320   {
00321     err=gentl->IFGetDeviceInfo(getParent()->getHandle(), id.c_str(),
00322                                GenTL::DEVICE_INFO_ACCESS_STATUS, &type, &status, &size);
00323   }
00324 
00325   if (err == GenTL::GC_ERR_SUCCESS)
00326   {
00327     if (type == GenTL::INFO_DATATYPE_INT32)
00328     {
00329       switch (status)
00330       {
00331         case GenTL::DEVICE_ACCESS_STATUS_READWRITE:
00332           ret="ReadWrite";
00333           break;
00334 
00335         case GenTL::DEVICE_ACCESS_STATUS_READONLY:
00336           ret="ReadOnly";
00337           break;
00338 
00339         case GenTL::DEVICE_ACCESS_STATUS_NOACCESS:
00340           ret="NoAccess";
00341           break;
00342 
00343         case GenTL::DEVICE_ACCESS_STATUS_BUSY:
00344           ret="Busy";
00345           break;
00346 
00347         case GenTL::DEVICE_ACCESS_STATUS_OPEN_READWRITE:
00348           ret="OpenReadWrite";
00349           break;
00350 
00351         case GenTL::DEVICE_ACCESS_STATUS_OPEN_READONLY:
00352           ret="OpenReadWrite";
00353           break;
00354 
00355         default:
00356           ret="Unknown";
00357           break;
00358       }
00359     }
00360   }
00361 
00362   return ret;
00363 }
00364 
00365 std::string Device::getUserDefinedName()
00366 {
00367   std::lock_guard<std::mutex> lock(mtx);
00368   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_USER_DEFINED_NAME);
00369 }
00370 
00371 std::string Device::getSerialNumber()
00372 {
00373   std::lock_guard<std::mutex> lock(mtx);
00374   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_SERIAL_NUMBER);
00375 }
00376 
00377 std::string Device::getVersion()
00378 {
00379   std::lock_guard<std::mutex> lock(mtx);
00380   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_VERSION);
00381 }
00382 
00383 uint64_t Device::getTimestampFrequency()
00384 {
00385   std::lock_guard<std::mutex> lock(mtx);
00386   GenTL::INFO_DATATYPE type;
00387   uint64_t freq=0;
00388   size_t size=sizeof(freq);
00389 
00390   if (dev != 0)
00391   {
00392     gentl->DevGetInfo(dev, GenTL::DEVICE_INFO_TIMESTAMP_FREQUENCY, &type, &freq, &size);
00393   }
00394   else if (parent->getHandle() != 0)
00395   {
00396     gentl->IFGetDeviceInfo(getParent()->getHandle(), id.c_str(),
00397                            GenTL::DEVICE_INFO_TIMESTAMP_FREQUENCY, &type, &freq, &size);
00398   }
00399 
00400   return freq;
00401 }
00402 
00403 std::shared_ptr<GenApi::CNodeMapRef> Device::getNodeMap()
00404 {
00405   std::lock_guard<std::mutex> lock(mtx);
00406 
00407   if (dev != 0 && !nodemap)
00408   {
00409     cport=std::shared_ptr<CPort>(new CPort(gentl, &dev));
00410     nodemap=allocNodeMap(gentl, dev, cport.get());
00411   }
00412 
00413   return nodemap;
00414 }
00415 
00416 std::shared_ptr<GenApi::CNodeMapRef> Device::getRemoteNodeMap(const char *xml)
00417 {
00418   std::lock_guard<std::mutex> lock(mtx);
00419 
00420   if (dev != 0 && !rnodemap)
00421   {
00422     if (gentl->DevGetPort(dev, &rp) == GenTL::GC_ERR_SUCCESS)
00423     {
00424       rport=std::shared_ptr<CPort>(new CPort(gentl, &rp));
00425       rnodemap=allocNodeMap(gentl, rp, rport.get(), xml);
00426     }
00427   }
00428 
00429   return rnodemap;
00430 }
00431 
00432 void *Device::getHandle() const
00433 {
00434   return dev;
00435 }
00436 
00437 std::vector<std::shared_ptr<Device> > getDevices()
00438 {
00439   std::vector<std::shared_ptr<Device> > ret;
00440 
00441   std::vector<std::shared_ptr<rcg::System> > system=rcg::System::getSystems();
00442 
00443   for (size_t i=0; i<system.size(); i++)
00444   {
00445     system[i]->open();
00446 
00447     std::vector<std::shared_ptr<rcg::Interface> > interf=system[i]->getInterfaces();
00448 
00449     for (size_t k=0; k<interf.size(); k++)
00450     {
00451       interf[k]->open();
00452 
00453       std::vector<std::shared_ptr<rcg::Device> > device=interf[k]->getDevices();
00454 
00455       for (size_t j=0; j<device.size(); j++)
00456       {
00457         ret.push_back(device[j]);
00458       }
00459 
00460       interf[k]->close();
00461     }
00462 
00463     system[i]->close();
00464   }
00465 
00466   return ret;
00467 }
00468 
00469 std::shared_ptr<Device> getDevice(const char *id)
00470 {
00471   std::shared_ptr<Device> ret;
00472 
00473   if (id != 0 && *id != '\0')
00474   {
00475     // split into interface and device id
00476 
00477     std::string interfid;
00478     std::string devid=id;
00479 
00480     size_t p=devid.find(':');
00481     if (p != std::string::npos)
00482     {
00483       interfid=devid.substr(0, p);
00484       devid=devid.substr(p+1);
00485     }
00486 
00487     // go through all systems
00488 
00489     std::vector<std::shared_ptr<rcg::System> > system=rcg::System::getSystems();
00490 
00491     for (size_t i=0; i<system.size() && !ret; i++)
00492     {
00493       system[i]->open();
00494 
00495       // get all interfaces
00496 
00497       std::vector<std::shared_ptr<rcg::Interface> > interf=system[i]->getInterfaces();
00498 
00499       if (interfid.size() > 0)
00500       {
00501         // if an interface is defined, then only search this interface
00502 
00503         for (size_t k=0; k<interf.size() && !ret; k++)
00504         {
00505           if (interf[k]->getID() == interfid)
00506           {
00507             interf[k]->open();
00508             ret=interf[k]->getDevice(devid.c_str());
00509             interf[k]->close();
00510           }
00511         }
00512       }
00513       else
00514       {
00515         // if interface is not defined, then check all interfaces
00516 
00517         for (size_t k=0; k<interf.size() && !ret; k++)
00518         {
00519           interf[k]->open();
00520           ret=interf[k]->getDevice(devid.c_str());
00521           interf[k]->close();
00522         }
00523       }
00524 
00525       system[i]->close();
00526     }
00527   }
00528 
00529   return ret;
00530 }
00531 
00532 }


rc_genicam_api
Author(s): Heiko Hirschmueller
autogenerated on Thu Jun 6 2019 18:42:46