system.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 "system.h"
00037 
00038 #include "gentl_wrapper.h"
00039 #include "exception.h"
00040 #include "interface.h"
00041 #include "cport.h"
00042 
00043 #include <iostream>
00044 
00045 #ifdef _WIN32
00046 #include <Windows.h>
00047 #include <cstring>
00048 #undef min
00049 #undef max
00050 #endif
00051 
00052 namespace rcg
00053 {
00054 
00055 System::~System()
00056 {
00057   if (n_open > 0 && tl != 0)
00058   {
00059     gentl->TLClose(tl);
00060   }
00061 
00062   gentl->GCCloseLib();
00063 }
00064 
00065 namespace
00066 {
00067 
00068 std::mutex system_mtx;
00069 std::vector<std::shared_ptr<System> > slist;
00070 
00071 int find(const std::vector<std::shared_ptr<System> > &list, const std::string &filename)
00072 {
00073   for (size_t i=0; i<list.size(); i++)
00074   {
00075     if (list[i]->getFilename() == filename)
00076     {
00077       return static_cast<int>(i);
00078     }
00079   }
00080 
00081   return -1;
00082 }
00083 
00084 #ifdef _WIN32
00085 static std::string getPathToThisDll()
00086 {
00087   HMODULE hm = nullptr;
00088   if (GetModuleHandleEx(
00089     GET_MODULE_HANDLE_EX_FLAG_FROM_ADDRESS |
00090     GET_MODULE_HANDLE_EX_FLAG_UNCHANGED_REFCOUNT,
00091     reinterpret_cast<LPCSTR>(&getPathToThisDll), &hm) == 0)
00092   {
00093     return {};
00094   }
00095 
00096   char path[MAX_PATH];
00097   if (GetModuleFileName(hm, path, sizeof(path)) == 0)
00098   {
00099     return {};
00100   }
00101 
00102   std::string p{ path };
00103   const auto bs_pos = p.rfind('\\');
00104   if (bs_pos != std::string::npos)
00105   {
00106     p = p.substr(0, bs_pos);
00107   }
00108 
00109   return p;
00110 }
00111 
00112 #endif
00113 
00114 }
00115 
00116 std::vector<std::shared_ptr<System> > System::getSystems()
00117 {
00118   std::lock_guard<std::mutex> lock(system_mtx);
00119   std::vector<std::shared_ptr<System> > ret;
00120 
00121   // get list of all available transport layer libraries
00122 
00123   const char *env=0;
00124   if (sizeof(size_t) == 8)
00125   {
00126     env="GENICAM_GENTL64_PATH";
00127   }
00128   else
00129   {
00130     env="GENICAM_GENTL32_PATH";
00131   }
00132 
00133   std::string path;
00134 
00135   const char *envpath=std::getenv(env);
00136   if (envpath != 0)
00137   {
00138     path=envpath;
00139   }
00140 
00141   if (path.size() == 0)
00142   {
00143 #ifdef _WIN32
00144     // under Windows, use the path to the current executable as fallback
00145 
00146     const size_t n=256;
00147     char procpath[n];
00148     std::string path_to_exe;
00149     if (GetModuleFileName(NULL, procpath, n-1) > 0)
00150     {
00151       procpath[n-1]='\0';
00152 
00153       char *p=strrchr(procpath, '\\');
00154       if (p != 0) *p='\0';
00155 
00156       path_to_exe=procpath;
00157       path+=";" + path_to_exe;
00158     }
00159 
00160     const auto path_to_this_dll = getPathToThisDll();
00161     if (!path_to_this_dll.empty() && path_to_this_dll != path_to_exe)
00162     {
00163       path += ";" + path_to_this_dll;
00164     }
00165 #else
00166     // otherwise, use the absolute install path to the default transport layer
00167 
00168     path=GENTL_INSTALL_PATH;
00169 #endif
00170   }
00171 
00172   std::vector<std::string> name=getAvailableGenTLs(path.c_str());
00173 
00174   // create list of systems according to the list, using either existing
00175   // systems or instantiating new ones
00176 
00177   for (size_t i=0; i<name.size(); i++)
00178   {
00179     int k=find(slist, name[i]);
00180 
00181     if (k >= 0)
00182     {
00183       ret.push_back(slist[static_cast<size_t>(k)]);
00184     }
00185     else
00186     {
00187       try
00188       {
00189         System *p=new System(name[i]);
00190         ret.push_back(std::shared_ptr<System>(p));
00191       }
00192       catch (const std::exception &)
00193       {
00194         // ignore transport layers that cannot be used
00195       }
00196     }
00197   }
00198 
00199   // remember returned list for reusing existing systems on the next call
00200 
00201   slist=ret;
00202 
00203   // throw exception if no transport layers are available
00204 
00205   if (ret.size() == 0)
00206   {
00207     throw GenTLException(std::string("No transport layers found in path ")+path);
00208   }
00209 
00210   return ret;
00211 }
00212 
00213 void System::clearSystems()
00214 {
00215   std::lock_guard<std::mutex> lock(system_mtx);
00216   slist.clear();
00217 }
00218 
00219 const std::string &System::getFilename() const
00220 {
00221   return filename;
00222 }
00223 
00224 void System::open()
00225 {
00226   std::lock_guard<std::mutex> lock(mtx);
00227 
00228   if (n_open == 0)
00229   {
00230     if (gentl->TLOpen(&tl) != GenTL::GC_ERR_SUCCESS)
00231     {
00232       throw GenTLException("System::open()", gentl);
00233     }
00234   }
00235 
00236   n_open++;
00237 }
00238 
00239 void System::close()
00240 {
00241   std::lock_guard<std::mutex> lock(mtx);
00242 
00243   if (n_open > 0)
00244   {
00245     n_open--;
00246   }
00247 
00248   if (n_open == 0)
00249   {
00250     gentl->TLClose(tl);
00251     tl=0;
00252 
00253     nodemap=0;
00254     cport=0;
00255   }
00256 }
00257 
00258 namespace
00259 {
00260 
00261 int find(const std::vector<std::shared_ptr<Interface> > &list, const std::string &id)
00262 {
00263   for (size_t i=0; i<list.size(); i++)
00264   {
00265     if (list[i]->getID() == id)
00266     {
00267       return static_cast<int>(i);
00268     }
00269   }
00270 
00271   return -1;
00272 }
00273 
00274 }
00275 
00276 std::vector<std::shared_ptr<Interface> > System::getInterfaces()
00277 {
00278   std::lock_guard<std::mutex> lock(mtx);
00279   std::vector<std::shared_ptr<Interface> > ret;
00280 
00281   if (tl != 0)
00282   {
00283     // get list of previously requested interfaces that are still in use
00284 
00285     std::vector<std::shared_ptr<Interface> > current;
00286 
00287     for (size_t i=0; i<ilist.size(); i++)
00288     {
00289       std::shared_ptr<Interface> p=ilist[i].lock();
00290       if (p)
00291       {
00292         current.push_back(p);
00293       }
00294     }
00295 
00296     // update available interfaces
00297 
00298     if (gentl->TLUpdateInterfaceList(tl, 0, 10) != GenTL::GC_ERR_SUCCESS)
00299     {
00300       throw GenTLException("System::getInterfaces()", gentl);
00301     }
00302 
00303     // create list of interfaces, using either existing interfaces or
00304     // instantiating new ones
00305 
00306     uint32_t n=0;
00307     if (gentl->TLGetNumInterfaces(tl, &n) != GenTL::GC_ERR_SUCCESS)
00308     {
00309       throw GenTLException("System::getInterfaces()", gentl);
00310     }
00311 
00312     for (uint32_t i=0; i<n; i++)
00313     {
00314       char tmp[256]="";
00315       size_t size=sizeof(tmp);
00316 
00317       if (gentl->TLGetInterfaceID(tl, i, tmp, &size) != GenTL::GC_ERR_SUCCESS)
00318       {
00319         throw GenTLException("System::getInterfaces()", gentl);
00320       }
00321 
00322       int k=find(current, tmp);
00323 
00324       if (k >= 0)
00325       {
00326         ret.push_back(current[static_cast<size_t>(k)]);
00327       }
00328       else
00329       {
00330         ret.push_back(std::shared_ptr<Interface>(new Interface(shared_from_this(), gentl, tmp)));
00331       }
00332     }
00333 
00334     // update internal list of interfaces for reusage on next call
00335 
00336     ilist.clear();
00337     for (size_t i=0; i<ret.size(); i++)
00338     {
00339       ilist.push_back(ret[i]);
00340     }
00341   }
00342 
00343   return ret;
00344 }
00345 
00346 namespace
00347 {
00348 
00349 std::string cTLGetInfo(GenTL::TL_HANDLE tl, const std::shared_ptr<const GenTLWrapper> &gentl,
00350                        GenTL::TL_INFO_CMD info)
00351 {
00352   std::string ret;
00353 
00354   GenTL::INFO_DATATYPE type;
00355   char tmp[1024]="";
00356   size_t tmp_size=sizeof(tmp);
00357   GenTL::GC_ERROR err=GenTL::GC_ERR_SUCCESS;
00358 
00359   if (tl != 0)
00360   {
00361     err=gentl->TLGetInfo(tl, info, &type, tmp, &tmp_size);
00362   }
00363   else
00364   {
00365     err=gentl->GCGetInfo(info, &type, tmp, &tmp_size);
00366   }
00367 
00368   if (err == GenTL::GC_ERR_SUCCESS && type == GenTL::INFO_DATATYPE_STRING)
00369   {
00370     for (size_t i=0; i<tmp_size && tmp[i] != '\0'; i++)
00371     {
00372       ret.push_back(tmp[i]);
00373     }
00374   }
00375 
00376   return ret;
00377 }
00378 
00379 }
00380 
00381 std::string System::getID()
00382 {
00383   std::lock_guard<std::mutex> lock(mtx);
00384   return cTLGetInfo(tl, gentl, GenTL::TL_INFO_ID);
00385 }
00386 
00387 std::string System::getVendor()
00388 {
00389   std::lock_guard<std::mutex> lock(mtx);
00390   return cTLGetInfo(tl, gentl, GenTL::TL_INFO_VENDOR);
00391 }
00392 
00393 std::string System::getModel()
00394 {
00395   std::lock_guard<std::mutex> lock(mtx);
00396   return cTLGetInfo(tl, gentl, GenTL::TL_INFO_MODEL);
00397 }
00398 
00399 std::string System::getVersion()
00400 {
00401   std::lock_guard<std::mutex> lock(mtx);
00402   return cTLGetInfo(tl, gentl, GenTL::TL_INFO_VERSION);
00403 }
00404 
00405 std::string System::getTLType()
00406 {
00407   std::lock_guard<std::mutex> lock(mtx);
00408   return cTLGetInfo(tl, gentl, GenTL::TL_INFO_TLTYPE);
00409 }
00410 
00411 std::string System::getName()
00412 {
00413   std::lock_guard<std::mutex> lock(mtx);
00414   return cTLGetInfo(tl, gentl, GenTL::TL_INFO_NAME);
00415 }
00416 
00417 std::string System::getPathname()
00418 {
00419   std::lock_guard<std::mutex> lock(mtx);
00420   return cTLGetInfo(tl, gentl, GenTL::TL_INFO_PATHNAME);
00421 }
00422 
00423 std::string System::getDisplayName()
00424 {
00425   std::lock_guard<std::mutex> lock(mtx);
00426   return cTLGetInfo(tl, gentl, GenTL::TL_INFO_DISPLAYNAME);
00427 }
00428 
00429 bool System::isCharEncodingASCII()
00430 {
00431   std::lock_guard<std::mutex> lock(mtx);
00432   bool ret=true;
00433 
00434   GenTL::INFO_DATATYPE type;
00435   int32_t v;
00436   size_t size=sizeof(v);
00437   GenTL::GC_ERROR err=GenTL::GC_ERR_SUCCESS;
00438 
00439   if (tl != 0)
00440   {
00441     err=gentl->TLGetInfo(tl, GenTL::TL_INFO_CHAR_ENCODING, &type, &v, &size);
00442   }
00443   else
00444   {
00445     err=gentl->GCGetInfo(GenTL::TL_INFO_CHAR_ENCODING, &type, &v, &size);
00446   }
00447 
00448   if (err == GenTL::GC_ERR_SUCCESS && type == GenTL::INFO_DATATYPE_INT32 &&
00449       v != GenTL::TL_CHAR_ENCODING_ASCII)
00450   {
00451     ret=false;
00452   }
00453 
00454   return ret;
00455 }
00456 
00457 int System::getMajorVersion()
00458 {
00459   std::lock_guard<std::mutex> lock(mtx);
00460   uint32_t ret=0;
00461 
00462   GenTL::INFO_DATATYPE type;
00463   size_t size=sizeof(ret);
00464 
00465   if (tl != 0)
00466   {
00467     gentl->TLGetInfo(tl, GenTL::TL_INFO_GENTL_VER_MAJOR, &type, &ret, &size);
00468   }
00469   else
00470   {
00471     gentl->GCGetInfo(GenTL::TL_INFO_GENTL_VER_MAJOR, &type, &ret, &size);
00472   }
00473 
00474   return static_cast<int>(ret);
00475 }
00476 
00477 int System::getMinorVersion()
00478 {
00479   std::lock_guard<std::mutex> lock(mtx);
00480   uint32_t ret=0;
00481 
00482   GenTL::INFO_DATATYPE type;
00483   size_t size=sizeof(ret);
00484 
00485   if (tl != 0)
00486   {
00487     gentl->TLGetInfo(tl, GenTL::TL_INFO_GENTL_VER_MINOR, &type, &ret, &size);
00488   }
00489   else
00490   {
00491     gentl->GCGetInfo(GenTL::TL_INFO_GENTL_VER_MINOR, &type, &ret, &size);
00492   }
00493 
00494   return static_cast<int>(ret);
00495 }
00496 
00497 std::shared_ptr<GenApi::CNodeMapRef> System::getNodeMap()
00498 {
00499   std::lock_guard<std::mutex> lock(mtx);
00500   if (tl != 0 && !nodemap)
00501   {
00502     cport=std::shared_ptr<CPort>(new CPort(gentl, &tl));
00503     nodemap=allocNodeMap(gentl, tl, cport.get());
00504   }
00505 
00506   return nodemap;
00507 }
00508 
00509 void *System::getHandle() const
00510 {
00511   return tl;
00512 }
00513 
00514 System::System(const std::string &_filename)
00515 {
00516   filename=_filename;
00517 
00518   gentl=std::shared_ptr<const GenTLWrapper>(new GenTLWrapper(filename));
00519 
00520   if (gentl->GCInitLib() != GenTL::GC_ERR_SUCCESS)
00521   {
00522     throw GenTLException("System::System()", gentl);
00523   }
00524 
00525   n_open=0;
00526   tl=0;
00527 }
00528 
00529 }


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