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   if (n_open == 0)
00088   {
00089     parent->open();
00090 
00091     GenTL::DEVICE_ACCESS_FLAGS mode;
00092 
00093     switch (access)
00094     {
00095       case READONLY:
00096         mode=GenTL::DEVICE_ACCESS_READONLY;
00097         break;
00098 
00099       case CONTROL:
00100         mode=GenTL::DEVICE_ACCESS_CONTROL;
00101         break;
00102 
00103       default:
00104       case EXCLUSIVE:
00105         mode=GenTL::DEVICE_ACCESS_EXCLUSIVE;
00106         break;
00107     }
00108 
00109     if (gentl->IFOpenDevice(parent->getHandle(), id.c_str(), mode, &dev) != GenTL::GC_ERR_SUCCESS)
00110     {
00111       parent->close();
00112       throw GenTLException("Device::open() failed", gentl);
00113     }
00114   }
00115 
00116   n_open++;
00117 }
00118 
00119 void Device::close()
00120 {
00121   if (n_open > 0)
00122   {
00123     n_open--;
00124   }
00125 
00126   if (n_open == 0)
00127   {
00128     gentl->DevClose(dev);
00129     dev=0;
00130     rp=0;
00131 
00132     nodemap=0;
00133     rnodemap=0;
00134 
00135     cport=0;
00136     rport=0;
00137 
00138     parent->close();
00139   }
00140 }
00141 
00142 namespace
00143 {
00144 
00145 int find(const std::vector<std::shared_ptr<Stream> > &list, const std::string &id)
00146 {
00147   for (size_t i=0; i<list.size(); i++)
00148   {
00149     if (list[i]->getID() == id)
00150     {
00151       return i;
00152     }
00153   }
00154 
00155   return -1;
00156 }
00157 
00158 }
00159 
00160 std::vector<std::shared_ptr<Stream> > Device::getStreams()
00161 {
00162   std::vector<std::shared_ptr<Stream> > ret;
00163 
00164   if (dev != 0)
00165   {
00166     // get list of previously requested devices that are still in use
00167 
00168     std::vector<std::shared_ptr<Stream> > current;
00169 
00170     for (size_t i=0; i<slist.size(); i++)
00171     {
00172       std::shared_ptr<Stream> p=slist[i].lock();
00173       if (p)
00174       {
00175         current.push_back(p);
00176       }
00177     }
00178 
00179     // create list of interfaces, using either existing interfaces or
00180     // instantiating new ones
00181 
00182     uint32_t n=0;
00183     if (gentl->DevGetNumDataStreams(dev, &n) != GenTL::GC_ERR_SUCCESS)
00184     {
00185       throw GenTLException("Device::getStreams()", gentl);
00186     }
00187 
00188     for (uint32_t i=0; i<n; i++)
00189     {
00190       char tmp[256]="";
00191       size_t size=sizeof(tmp);
00192 
00193       if (gentl->DevGetDataStreamID(dev, i, tmp, &size) != GenTL::GC_ERR_SUCCESS)
00194       {
00195         throw GenTLException("Device::getStreams()", gentl);
00196       }
00197 
00198       int k=find(current, tmp);
00199 
00200       if (k >= 0)
00201       {
00202         ret.push_back(current[k]);
00203       }
00204       else
00205       {
00206         ret.push_back(std::shared_ptr<Stream>(new Stream(shared_from_this(), gentl, tmp)));
00207       }
00208     }
00209 
00210     // update internal list of devices for reusage on next call
00211 
00212     slist.clear();
00213     for (size_t i=0; i<ret.size(); i++)
00214     {
00215       slist.push_back(ret[i]);
00216     }
00217   }
00218 
00219   return ret;
00220 
00221 }
00222 
00223 namespace
00224 {
00225 
00226 std::string cDevGetInfo(const Device *obj, const std::shared_ptr<const GenTLWrapper> &gentl,
00227                         GenTL::DEVICE_INFO_CMD info)
00228 {
00229   std::string ret;
00230 
00231   GenTL::INFO_DATATYPE type;
00232   char tmp[1024]="";
00233   size_t tmp_size=sizeof(tmp);
00234   GenTL::GC_ERROR err=GenTL::GC_ERR_ERROR;
00235 
00236   if (obj->getHandle() != 0)
00237   {
00238     err=gentl->DevGetInfo(obj->getHandle(), info, &type, tmp, &tmp_size);
00239   }
00240   else if (obj->getParent()->getHandle() != 0)
00241   {
00242     err=gentl->IFGetDeviceInfo(obj->getParent()->getHandle(), obj->getID().c_str(), info, &type,
00243                                tmp, &tmp_size);
00244   }
00245 
00246   if (err == GenTL::GC_ERR_SUCCESS && type == GenTL::INFO_DATATYPE_STRING)
00247   {
00248     for (size_t i=0; i<tmp_size && tmp[i] != '\0'; i++)
00249     {
00250       ret.push_back(tmp[i]);
00251     }
00252   }
00253 
00254   return ret;
00255 }
00256 
00257 }
00258 
00259 std::string Device::getVendor() const
00260 {
00261   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_VENDOR);
00262 }
00263 
00264 std::string Device::getModel() const
00265 {
00266   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_MODEL);
00267 }
00268 
00269 std::string Device::getTLType() const
00270 {
00271   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_TLTYPE);
00272 }
00273 
00274 std::string Device::getDisplayName() const
00275 {
00276   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_DISPLAYNAME);
00277 }
00278 
00279 std::string Device::getAccessStatus() const
00280 {
00281   std::string ret;
00282 
00283   GenTL::INFO_DATATYPE type;
00284   int32_t status=-1;
00285   size_t size=sizeof(ret);
00286   GenTL::GC_ERROR err=GenTL::GC_ERR_ERROR;
00287 
00288   if (dev != 0)
00289   {
00290     err=gentl->DevGetInfo(dev, GenTL::DEVICE_INFO_ACCESS_STATUS, &type, &status, &size);
00291   }
00292   else if (parent->getHandle() != 0)
00293   {
00294     err=gentl->IFGetDeviceInfo(getParent()->getHandle(), id.c_str(),
00295                                GenTL::DEVICE_INFO_ACCESS_STATUS, &type, &status, &size);
00296   }
00297 
00298   if (err == GenTL::GC_ERR_SUCCESS)
00299   {
00300     if (type == GenTL::INFO_DATATYPE_INT32)
00301     {
00302       switch (status)
00303       {
00304         case GenTL::DEVICE_ACCESS_STATUS_READWRITE:
00305           ret="ReadWrite";
00306           break;
00307 
00308         case GenTL::DEVICE_ACCESS_STATUS_READONLY:
00309           ret="ReadOnly";
00310           break;
00311 
00312         case GenTL::DEVICE_ACCESS_STATUS_NOACCESS:
00313           ret="NoAccess";
00314           break;
00315 
00316         case GenTL::DEVICE_ACCESS_STATUS_BUSY:
00317           ret="Busy";
00318           break;
00319 
00320         case GenTL::DEVICE_ACCESS_STATUS_OPEN_READWRITE:
00321           ret="OpenReadWrite";
00322           break;
00323 
00324         case GenTL::DEVICE_ACCESS_STATUS_OPEN_READONLY:
00325           ret="OpenReadWrite";
00326           break;
00327 
00328         default:
00329           ret="Unknown";
00330           break;
00331       }
00332     }
00333   }
00334 
00335   return ret;
00336 }
00337 
00338 std::string Device::getUserDefinedName() const
00339 {
00340   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_USER_DEFINED_NAME);
00341 }
00342 
00343 std::string Device::getSerialNumber() const
00344 {
00345   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_SERIAL_NUMBER);
00346 }
00347 
00348 std::string Device::getVersion() const
00349 {
00350   return cDevGetInfo(this, gentl, GenTL::DEVICE_INFO_VERSION);
00351 }
00352 
00353 uint64_t Device::getTimestampFrequency() const
00354 {
00355   GenTL::INFO_DATATYPE type;
00356   uint64_t freq=0;
00357   size_t size=sizeof(freq);
00358 
00359   if (dev != 0)
00360   {
00361     gentl->DevGetInfo(dev, GenTL::DEVICE_INFO_TIMESTAMP_FREQUENCY, &type, &freq, &size);
00362   }
00363   else if (parent->getHandle() != 0)
00364   {
00365     gentl->IFGetDeviceInfo(getParent()->getHandle(), id.c_str(),
00366                            GenTL::DEVICE_INFO_TIMESTAMP_FREQUENCY, &type, &freq, &size);
00367   }
00368 
00369   return freq;
00370 }
00371 
00372 std::shared_ptr<GenApi::CNodeMapRef> Device::getNodeMap()
00373 {
00374   if (dev != 0 && !nodemap)
00375   {
00376     cport=std::shared_ptr<CPort>(new CPort(gentl, &dev));
00377     nodemap=allocNodeMap(gentl, dev, cport.get());
00378   }
00379 
00380   return nodemap;
00381 }
00382 
00383 std::shared_ptr<GenApi::CNodeMapRef> Device::getRemoteNodeMap(const char *xml)
00384 {
00385   if (dev != 0 && !rnodemap)
00386   {
00387     if (gentl->DevGetPort(dev, &rp) == GenTL::GC_ERR_SUCCESS)
00388     {
00389       rport=std::shared_ptr<CPort>(new CPort(gentl, &rp));
00390       rnodemap=allocNodeMap(gentl, rp, rport.get(), xml);
00391     }
00392   }
00393 
00394   return rnodemap;
00395 }
00396 
00397 void *Device::getHandle() const
00398 {
00399   return dev;
00400 }
00401 
00402 std::vector<std::shared_ptr<Device> > getDevices()
00403 {
00404   std::vector<std::shared_ptr<Device> > ret;
00405 
00406   std::vector<std::shared_ptr<rcg::System> > system=rcg::System::getSystems();
00407 
00408   for (size_t i=0; i<system.size(); i++)
00409   {
00410     system[i]->open();
00411 
00412     std::vector<std::shared_ptr<rcg::Interface> > interf=system[i]->getInterfaces();
00413 
00414     for (size_t k=0; k<interf.size(); k++)
00415     {
00416       interf[k]->open();
00417 
00418       std::vector<std::shared_ptr<rcg::Device> > device=interf[k]->getDevices();
00419 
00420       for (size_t j=0; j<device.size(); j++)
00421       {
00422         ret.push_back(device[j]);
00423       }
00424 
00425       interf[k]->close();
00426     }
00427 
00428     system[i]->close();
00429   }
00430 
00431   return ret;
00432 }
00433 
00434 std::shared_ptr<Device> getDevice(const char *id)
00435 {
00436   std::shared_ptr<Device> ret;
00437 
00438   if (id != 0 && *id != '\0')
00439   {
00440     // split into interface and device id
00441 
00442     std::string interfid;
00443     std::string devid=id;
00444 
00445     size_t p=devid.find(':');
00446     if (p != std::string::npos)
00447     {
00448       interfid=devid.substr(0, p);
00449       devid=devid.substr(p+1);
00450     }
00451 
00452     // go through all systems
00453 
00454     std::vector<std::shared_ptr<rcg::System> > system=rcg::System::getSystems();
00455 
00456     for (size_t i=0; i<system.size() && !ret; i++)
00457     {
00458       system[i]->open();
00459 
00460       // get all interfaces
00461 
00462       std::vector<std::shared_ptr<rcg::Interface> > interf=system[i]->getInterfaces();
00463 
00464       if (interfid.size() > 0)
00465       {
00466         // if an interface is defined, then only search this interface
00467 
00468         for (size_t k=0; k<interf.size() && !ret; k++)
00469         {
00470           if (interf[k]->getID() == interfid)
00471           {
00472             interf[k]->open();
00473             ret=interf[k]->getDevice(devid.c_str());
00474             interf[k]->close();
00475           }
00476         }
00477       }
00478       else
00479       {
00480         // if interface is not defined, then check all interfaces
00481 
00482         for (size_t k=0; k<interf.size() && !ret; k++)
00483         {
00484           interf[k]->open();
00485           ret=interf[k]->getDevice(devid.c_str());
00486           interf[k]->close();
00487         }
00488       }
00489 
00490       system[i]->close();
00491     }
00492   }
00493 
00494   return ret;
00495 }
00496 
00497 }


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Thu Jun 6 2019 20:43:02