gentl_wrapper_linux.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 "gentl_wrapper.h"
00037 
00038 #include <string>
00039 #include <sstream>
00040 #include <stdexcept>
00041 #include <cstdlib>
00042 #include <iostream>
00043 
00044 #include <dlfcn.h>
00045 #include <dirent.h>
00046 
00047 namespace rcg
00048 {
00049 
00050 std::vector<std::string> getAvailableGenTLs(const char *paths)
00051 {
00052   std::vector<std::string> ret;
00053 
00054   if (paths != 0)
00055   {
00056     // split path list into individual paths
00057 
00058     std::stringstream in(paths);
00059     std::string path;
00060 
00061     while (getline(in, path, ':'))
00062     {
00063       if (path.size() > 0)
00064       {
00065         if (path.size() > 4 && path.compare(path.size()-4, 4, ".cti") == 0)
00066         {
00067           // the given path points to one file ending with .cti
00068 
00069           ret.push_back(path);
00070         }
00071         else
00072         {
00073           // try to instantiate GenTLWrapper for all files in the given path that
00074           // end with .cti
00075 
00076           DIR *p=opendir(path.c_str());
00077 
00078           if (p != 0)
00079           {
00080             struct dirent *entry=readdir(p);
00081 
00082             while (entry != 0)
00083             {
00084               std::string name=entry->d_name;
00085 
00086               if (name.size() >= 4 && name.compare(name.size()-4, 4, ".cti") == 0)
00087               {
00088                 ret.push_back(path+"/"+name);
00089               }
00090 
00091               entry=readdir(p);
00092             }
00093 
00094             closedir(p);
00095           }
00096         }
00097       }
00098     }
00099   }
00100 
00101   return ret;
00102 }
00103 
00104 GenTLWrapper::GenTLWrapper(const std::string &filename)
00105 {
00106   // open library
00107 
00108   // NOTE: RTLD_DEEPBIND is necessary for resolving symbols of the loaded
00109   // library locally before using global symbols. This is for example needed
00110   // if rc_genicam_api is used in a ROS node or nodelet and a transport layer
00111   // library internally uses boost in a different version as in ROS.
00112 
00113   lib=dlopen(filename.c_str(), RTLD_NOW | RTLD_DEEPBIND);
00114 
00115   if (lib == 0)
00116   {
00117     throw std::invalid_argument(std::string("Cannot open GenTL library: ")+dlerror());
00118   }
00119 
00120   dlerror(); // clear possible existing error
00121 
00122   // resolve function calls that will only be used privately
00123 
00124   *reinterpret_cast<void**>(&GCInitLib)=dlsym(lib, "GCInitLib");
00125   *reinterpret_cast<void**>(&GCCloseLib)=dlsym(lib, "GCCloseLib");
00126 
00127   // resolve public symbols
00128 
00129   *reinterpret_cast<void**>(&GCGetInfo)=dlsym(lib, "GCGetInfo");
00130   *reinterpret_cast<void**>(&GCGetLastError)=dlsym(lib, "GCGetLastError");
00131   *reinterpret_cast<void**>(&GCReadPort)=dlsym(lib, "GCReadPort");
00132   *reinterpret_cast<void**>(&GCWritePort)=dlsym(lib, "GCWritePort");
00133   *reinterpret_cast<void**>(&GCGetPortURL)=dlsym(lib, "GCGetPortURL");
00134   *reinterpret_cast<void**>(&GCGetPortInfo)=dlsym(lib, "GCGetPortInfo");
00135 
00136   *reinterpret_cast<void**>(&GCRegisterEvent)=dlsym(lib, "GCRegisterEvent");
00137   *reinterpret_cast<void**>(&GCUnregisterEvent)=dlsym(lib, "GCUnregisterEvent");
00138   *reinterpret_cast<void**>(&EventGetData)=dlsym(lib, "EventGetData");
00139   *reinterpret_cast<void**>(&EventGetDataInfo)=dlsym(lib, "EventGetDataInfo");
00140   *reinterpret_cast<void**>(&EventGetInfo)=dlsym(lib, "EventGetInfo");
00141   *reinterpret_cast<void**>(&EventFlush)=dlsym(lib, "EventFlush");
00142   *reinterpret_cast<void**>(&EventKill)=dlsym(lib, "EventKill");
00143   *reinterpret_cast<void**>(&TLOpen)=dlsym(lib, "TLOpen");
00144   *reinterpret_cast<void**>(&TLClose)=dlsym(lib, "TLClose");
00145   *reinterpret_cast<void**>(&TLGetInfo)=dlsym(lib, "TLGetInfo");
00146   *reinterpret_cast<void**>(&TLGetNumInterfaces)=dlsym(lib, "TLGetNumInterfaces");
00147   *reinterpret_cast<void**>(&TLGetInterfaceID)=dlsym(lib, "TLGetInterfaceID");
00148   *reinterpret_cast<void**>(&TLGetInterfaceInfo)=dlsym(lib, "TLGetInterfaceInfo");
00149   *reinterpret_cast<void**>(&TLOpenInterface)=dlsym(lib, "TLOpenInterface");
00150   *reinterpret_cast<void**>(&TLUpdateInterfaceList)=dlsym(lib, "TLUpdateInterfaceList");
00151   *reinterpret_cast<void**>(&IFClose)=dlsym(lib, "IFClose");
00152   *reinterpret_cast<void**>(&IFGetInfo)=dlsym(lib, "IFGetInfo");
00153   *reinterpret_cast<void**>(&IFGetNumDevices)=dlsym(lib, "IFGetNumDevices");
00154   *reinterpret_cast<void**>(&IFGetDeviceID)=dlsym(lib, "IFGetDeviceID");
00155   *reinterpret_cast<void**>(&IFUpdateDeviceList)=dlsym(lib, "IFUpdateDeviceList");
00156   *reinterpret_cast<void**>(&IFGetDeviceInfo)=dlsym(lib, "IFGetDeviceInfo");
00157   *reinterpret_cast<void**>(&IFOpenDevice)=dlsym(lib, "IFOpenDevice");
00158 
00159   *reinterpret_cast<void**>(&DevGetPort)=dlsym(lib, "DevGetPort");
00160   *reinterpret_cast<void**>(&DevGetNumDataStreams)=dlsym(lib, "DevGetNumDataStreams");
00161   *reinterpret_cast<void**>(&DevGetDataStreamID)=dlsym(lib, "DevGetDataStreamID");
00162   *reinterpret_cast<void**>(&DevOpenDataStream)=dlsym(lib, "DevOpenDataStream");
00163   *reinterpret_cast<void**>(&DevGetInfo)=dlsym(lib, "DevGetInfo");
00164   *reinterpret_cast<void**>(&DevClose)=dlsym(lib, "DevClose");
00165 
00166   *reinterpret_cast<void**>(&DSAnnounceBuffer)=dlsym(lib, "DSAnnounceBuffer");
00167   *reinterpret_cast<void**>(&DSAllocAndAnnounceBuffer)=dlsym(lib, "DSAllocAndAnnounceBuffer");
00168   *reinterpret_cast<void**>(&DSFlushQueue)=dlsym(lib, "DSFlushQueue");
00169   *reinterpret_cast<void**>(&DSStartAcquisition)=dlsym(lib, "DSStartAcquisition");
00170   *reinterpret_cast<void**>(&DSStopAcquisition)=dlsym(lib, "DSStopAcquisition");
00171   *reinterpret_cast<void**>(&DSGetInfo)=dlsym(lib, "DSGetInfo");
00172   *reinterpret_cast<void**>(&DSGetBufferID)=dlsym(lib, "DSGetBufferID");
00173   *reinterpret_cast<void**>(&DSClose)=dlsym(lib, "DSClose");
00174   *reinterpret_cast<void**>(&DSRevokeBuffer)=dlsym(lib, "DSRevokeBuffer");
00175   *reinterpret_cast<void**>(&DSQueueBuffer)=dlsym(lib, "DSQueueBuffer");
00176   *reinterpret_cast<void**>(&DSGetBufferInfo)=dlsym(lib, "DSGetBufferInfo");
00177 
00178   *reinterpret_cast<void**>(&GCGetNumPortURLs)=dlsym(lib, "GCGetNumPortURLs");
00179   *reinterpret_cast<void**>(&GCGetPortURLInfo)=dlsym(lib, "GCGetPortURLInfo");
00180   *reinterpret_cast<void**>(&GCReadPortStacked)=dlsym(lib, "GCReadPortStacked");
00181   *reinterpret_cast<void**>(&GCWritePortStacked)=dlsym(lib, "GCWritePortStacked");
00182 
00183   *reinterpret_cast<void**>(&DSGetBufferChunkData)=dlsym(lib, "DSGetBufferChunkData");
00184 
00185   *reinterpret_cast<void**>(&IFGetParentTL)=dlsym(lib, "IFGetParentTL");
00186   *reinterpret_cast<void**>(&DevGetParentIF)=dlsym(lib, "DevGetParentIF");
00187   *reinterpret_cast<void**>(&DSGetParentDev)=dlsym(lib, "DSGetParentDev");
00188 
00189   *reinterpret_cast<void**>(&DSGetNumBufferParts)=dlsym(lib, "DSGetNumBufferParts");
00190   *reinterpret_cast<void**>(&DSGetBufferPartInfo)=dlsym(lib, "DSGetBufferPartInfo");
00191 
00192   const char *err=dlerror();
00193 
00194   if (err != 0)
00195   {
00196     dlclose(lib);
00197     throw std::invalid_argument(std::string("Cannot resolve GenTL symbol: ")+err);
00198   }
00199 }
00200 
00201 GenTLWrapper::~GenTLWrapper()
00202 {
00203   dlclose(lib);
00204 }
00205 
00206 }


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