Fix ROOT-10484 by implementing dyld support for RPATH.

Some libraries are layered can depend on other libraries on a private paths.
That is, libA can depend on libB which is neither on the LD_LIBRARY_PATH nor
on a known system path. The posix linker injects "variables" such as @rpath
which is expanded at link time to resolve the libraries on a relative path.

Prior to this patch, cling's Dyld-based symbol resolution could not trace down
such cases causing failures in symbol resolution when a symbol is only defined
in libB (a private library).

This patch implements the basic posix linker substitutions allowing cling's
Dyld-based symbol resolution implementation to follow more closely the linker
rules.

Kudos Alexander Penev (@alexander-penev).
This commit is contained in:
Vassil Vassilev 2020-12-19 22:22:06 +00:00 committed by jenkins
parent 03e02c57bb
commit 55a4e89b3b
40 changed files with 1688 additions and 152 deletions

View File

@ -68,22 +68,35 @@ namespace cling {
///\brief Concatenates current include paths and the system include paths
/// and performs a lookup for the filename.
/// See more information for RPATH and RUNPATH: https://en.wikipedia.org/wiki/Rpath
///\param[in] libStem - The filename being looked up
///\param[in] RPath - RPATH as provided by loader library, searching for libStem
///\param[in] RunPath - RUNPATH as provided by loader library, searching for libStem
///\param[in] libLoader - The library that loads libStem. Use "" for main program.
///
///\returns the canonical path to the file or empty string if not found
///
std::string lookupLibInPaths(llvm::StringRef libStem) const;
std::string lookupLibInPaths(llvm::StringRef libStem,
llvm::SmallVector<llvm::StringRef,2> RPath = {},
llvm::SmallVector<llvm::StringRef,2> RunPath = {},
llvm::StringRef libLoader = "") const;
///\brief Concatenates current include paths and the system include paths
/// and performs a lookup for the filename. If still not found it tries to
/// add the platform-specific extensions (such as so, dll, dylib) and
/// retries the lookup (from lookupLibInPaths)
/// See more information for RPATH and RUNPATH: https://en.wikipedia.org/wiki/Rpath
///\param[in] filename - The filename being looked up
///\param[in] RPath - RPATH as provided by loader library, searching for libStem
///\param[in] RunPath - RUNPATH as provided by loader library, searching for libStem
///\param[in] libLoader - The library that loads libStem. Use "" for main program.
///
///\returns the canonical path to the file or empty string if not found
///
std::string lookupLibMaybeAddExt(llvm::StringRef filename) const;
std::string lookupLibMaybeAddExt(llvm::StringRef filename,
llvm::SmallVector<llvm::StringRef,2> RPath = {},
llvm::SmallVector<llvm::StringRef,2> RunPath = {},
llvm::StringRef libLoader = "") const;
/// On a success returns to full path to a shared object that holds the
/// symbol pointed by func.
@ -109,17 +122,31 @@ namespace cling {
void addSearchPath(llvm::StringRef dir, bool isUser = true,
bool prepend = false) {
auto pos = prepend ? m_SearchPaths.begin() : m_SearchPaths.end();
m_SearchPaths.insert(pos, SearchPathInfo{dir, isUser});
if (!dir.empty()) {
for (auto & item : m_SearchPaths)
if (dir.equals(item.Path)) return;
auto pos = prepend ? m_SearchPaths.begin() : m_SearchPaths.end();
m_SearchPaths.insert(pos, SearchPathInfo{dir, isUser});
}
}
///\brief Looks up a library taking into account the current include paths
/// and the system include paths.
/// See more information for RPATH and RUNPATH: https://en.wikipedia.org/wiki/Rpath
///\param[in] libStem - The filename being looked up
///\param[in] RPath - RPATH as provided by loader library, searching for libStem
///\param[in] RunPath - RUNPATH as provided by loader library, searching for libStem
///\param[in] libLoader - The library that loads libStem. Use "" for main program.
///\param[in] variateLibStem - If this param is true, and libStem is "L", then
/// we search for "L", "libL", "L.so", "libL.so"", etc.
///
///\returns the canonical path to the file or empty string if not found
///
std::string lookupLibrary(llvm::StringRef libStem) const;
std::string lookupLibrary(llvm::StringRef libStem,
llvm::SmallVector<llvm::StringRef,2> RPath = {},
llvm::SmallVector<llvm::StringRef,2> RunPath = {},
llvm::StringRef libLoader = "",
bool variateLibStem = true) const;
///\brief Loads a shared library.
///
@ -132,7 +159,7 @@ namespace cling {
/// was already loaded, kLoadLibError if the library cannot be found or any
/// other error was encountered.
///
LoadLibResult loadLibrary(const std::string& libStem, bool permanent,
LoadLibResult loadLibrary(llvm::StringRef, bool permanent,
bool resolved = false);
void unloadLibrary(llvm::StringRef libStem);
@ -158,7 +185,7 @@ namespace cling {
///
///\returns the library name if found, and empty string otherwise.
///
std::string searchLibrariesForSymbol(const std::string& mangledName,
std::string searchLibrariesForSymbol(llvm::StringRef mangledName,
bool searchSystem = true) const;
void dump(llvm::raw_ostream* S = nullptr) const;

View File

@ -13,6 +13,7 @@
#include "cling/Utils/Platform.h"
#include "cling/Utils/Output.h"
#include "llvm/ADT/StringSet.h"
#include "llvm/BinaryFormat/Magic.h"
#include "llvm/Support/DynamicLibrary.h"
#include "llvm/Support/Path.h"
@ -20,6 +21,9 @@
#include <system_error>
#include <sys/stat.h>
// FIXME: Implement debugging output stream in cling.
constexpr unsigned DEBUG = 0;
namespace cling {
DynamicLibraryManager::DynamicLibraryManager() {
const llvm::SmallVector<const char*, 10> kSysLibraryEnv = {
@ -45,7 +49,7 @@ namespace cling {
llvm::SmallVector<llvm::StringRef, 10> CurPaths;
SplitPaths(Env, CurPaths, utils::kPruneNonExistant, platform::kEnvDelim);
for (const auto& Path : CurPaths)
addSearchPath(Path.str());
addSearchPath(Path);
}
}
@ -59,26 +63,164 @@ namespace cling {
addSearchPath(P, /*IsUser*/ false);
}
///\returns substitution of pattern in the front of original with replacement
/// Example: substFront("@rpath/abc", "@rpath/", "/tmp") -> "/tmp/abc"
static std::string substFront(llvm::StringRef original, llvm::StringRef pattern,
llvm::StringRef replacement) {
if (!original.startswith_lower(pattern))
return original.str();
llvm::SmallString<512> result(replacement);
result.append(original.drop_front(pattern.size()));
return result.str();
}
///\returns substitution of all known linker variables in \c original
static std::string substAll(llvm::StringRef original,
llvm::StringRef libLoader) {
// Handle substitutions (MacOS):
// @rpath - This function does not substitute @rpath, becouse
// this variable is already handled by lookupLibrary where
// @rpath is replaced with all paths from RPATH one by one.
// @executable_path - Main program path.
// @loader_path - Loader library (or main program) path.
//
// Handle substitutions (Linux):
// https://man7.org/linux/man-pages/man8/ld.so.8.html
// $origin - Loader library (or main program) path.
// $lib - lib lib64
// $platform - x86_64 AT_PLATFORM
std::string result;
#ifdef __APPLE__
llvm::SmallString<512> mainExecutablePath(llvm::sys::fs::getMainExecutable(nullptr, nullptr));
llvm::sys::path::remove_filename(mainExecutablePath);
llvm::SmallString<512> loaderPath;
if (libLoader.empty()) {
loaderPath = mainExecutablePath;
} else {
loaderPath = libLoader.str();
llvm::sys::path::remove_filename(loaderPath);
}
result = substFront(original, "@executable_path", mainExecutablePath);
result = substFront(result, "@loader_path", loaderPath);
return result;
#else
llvm::SmallString<512> loaderPath;
if (libLoader.empty()) {
loaderPath = llvm::sys::fs::getMainExecutable(nullptr, nullptr);
} else {
loaderPath = libLoader.str();
}
llvm::sys::path::remove_filename(loaderPath);
result = substFront(original, "$origin", loaderPath);
//result = substFront(result, "$lib", true?"lib":"lib64");
//result = substFront(result, "$platform", "x86_64");
return result;
#endif
}
std::string
DynamicLibraryManager::lookupLibInPaths(llvm::StringRef libStem) const {
DynamicLibraryManager::lookupLibInPaths(llvm::StringRef libStem,
llvm::SmallVector<llvm::StringRef,2> RPath /*={}*/,
llvm::SmallVector<llvm::StringRef,2> RunPath /*={}*/,
llvm::StringRef libLoader /*=""*/) const {
if (DEBUG > 7) {
cling::errs() << "Dyld::lookupLibInPaths:" << libStem.str() <<
", ..., libLodaer=" << libLoader << "\n";
}
// Lookup priority is: RPATH, LD_LIBRARY_PATH/m_SearchPaths, RUNPATH
// See: https://en.wikipedia.org/wiki/Rpath
// See: https://amir.rachum.com/blog/2016/09/17/shared-libraries/
if (DEBUG > 7) {
cling::errs() << "Dyld::lookupLibInPaths: \n";
cling::errs() << ":: RPATH\n";
for (auto Info : RPath) {
cling::errs() << ":::: " << Info.str() << "\n";
}
cling::errs() << ":: SearchPaths (LD_LIBRARY_PATH, etc...)\n";
for (auto Info : getSearchPaths()) {
cling::errs() << ":::: " << Info.Path << ", user=" << (Info.IsUser?"true":"false") << "\n";
}
cling::errs() << ":: RUNPATH\n";
for (auto Info : RunPath) {
cling::errs() << ":::: " << Info.str() << "\n";
}
}
llvm::SmallString<512> ThisPath;
// RPATH
for (auto Info : RPath) {
ThisPath = substAll(Info, libLoader);
llvm::sys::path::append(ThisPath, libStem);
// to absolute path?
if (DEBUG > 7) {
cling::errs() << "## Try: " << ThisPath;
}
if (isSharedLibrary(ThisPath.str())) {
if (DEBUG > 7) {
cling::errs() << " ... Found (in RPATH)!\n";
}
return ThisPath.str();
}
}
// m_SearchPaths
for (const SearchPathInfo& Info : m_SearchPaths) {
ThisPath = Info.Path;
llvm::sys::path::append(ThisPath, libStem);
bool exists;
if (isSharedLibrary(ThisPath.str(), &exists))
// to absolute path?
if (DEBUG > 7) {
cling::errs() << "## Try: " << ThisPath;
}
if (isSharedLibrary(ThisPath.str())) {
if (DEBUG > 7) {
cling::errs() << " ... Found (in SearchPaths)!\n";
}
return ThisPath.str();
if (exists)
return "";
}
}
// RUNPATH
for (auto Info : RunPath) {
ThisPath = substAll(Info, libLoader);
llvm::sys::path::append(ThisPath, libStem);
// to absolute path?
if (DEBUG > 7) {
cling::errs() << "## Try: " << ThisPath;
}
if (isSharedLibrary(ThisPath.str())) {
if (DEBUG > 7) {
cling::errs() << " ... Found (in RUNPATH)!\n";
}
return ThisPath.str();
}
}
if (DEBUG > 7) {
cling::errs() << "## NotFound!!!\n";
}
return "";
}
std::string
DynamicLibraryManager::lookupLibMaybeAddExt(llvm::StringRef libStem) const {
DynamicLibraryManager::lookupLibMaybeAddExt(llvm::StringRef libStem,
llvm::SmallVector<llvm::StringRef,2> RPath /*={}*/,
llvm::SmallVector<llvm::StringRef,2> RunPath /*={}*/,
llvm::StringRef libLoader /*=""*/) const {
using namespace llvm::sys;
std::string foundDyLib = lookupLibInPaths(libStem);
if (DEBUG > 7) {
cling::errs() << "Dyld::lookupLibMaybeAddExt: " << libStem.str() <<
", ..., libLoader=" << libLoader << "\n";
}
std::string foundDyLib = lookupLibInPaths(libStem, RPath, RunPath, libLoader);
if (foundDyLib.empty()) {
// Add DyLib extension:
@ -94,12 +236,12 @@ namespace cling {
# error "Unsupported platform."
#endif
filenameWithExt += DyLibExt;
foundDyLib = lookupLibInPaths(filenameWithExt);
foundDyLib = lookupLibInPaths(filenameWithExt, RPath, RunPath, libLoader);
#ifdef __APPLE__
if (foundDyLib.empty()) {
filenameWithExt.erase(IStemEnd + 1, filenameWithExt.end());
filenameWithExt += ".dylib";
foundDyLib = lookupLibInPaths(filenameWithExt);
foundDyLib = lookupLibInPaths(filenameWithExt, RPath, RunPath, libLoader);
}
#endif
}
@ -130,8 +272,28 @@ namespace cling {
return NPath;
}
std::string RPathToStr2(llvm::SmallVector<llvm::StringRef,2> V) {
std::string result;
for (auto item : V)
result += item.str() + ",";
if (!result.empty())
result.pop_back();
return result;
}
std::string
DynamicLibraryManager::lookupLibrary(llvm::StringRef libStem) const {
DynamicLibraryManager::lookupLibrary(llvm::StringRef libStem,
llvm::SmallVector<llvm::StringRef,2> RPath /*={}*/,
llvm::SmallVector<llvm::StringRef,2> RunPath /*={}*/,
// llvm::StringRef RPath /*=""*/,
// llvm::StringRef RunPath /*=""*/,
llvm::StringRef libLoader /*=""*/,
bool variateLibStem /*=true*/) const {
if (DEBUG > 7) {
cling::errs() << "Dyld::lookupLibrary: " << libStem.str() << ", " <<
RPathToStr2(RPath) << ", " << RPathToStr2(RunPath) << ", " << libLoader.str() << "\n";
}
// If it is an absolute path, don't try iterate over the paths.
if (llvm::sys::path::is_absolute(libStem)) {
if (isSharedLibrary(libStem))
@ -140,23 +302,61 @@ namespace cling {
return std::string();
}
std::string foundName = lookupLibMaybeAddExt(libStem);
if (foundName.empty() && !libStem.startswith("lib")) {
// try with "lib" prefix:
foundName = lookupLibMaybeAddExt("lib" + libStem.str());
// Subst all known linker variables ($origin, @rpath, etc.)
#ifdef __APPLE__
// On MacOS @rpath is preplaced by all paths in RPATH one by one.
if (libStem.startswith_lower("@rpath")) {
for (auto& P : RPath) {
std::string result = substFront(libStem, "@rpath", P);
if (isSharedLibrary(result))
return normalizePath(result);
}
} else {
#endif
std::string result = substAll(libStem, libLoader);
if (isSharedLibrary(result))
return normalizePath(result);
#ifdef __APPLE__
}
#endif
// Expand libStem with paths, extensions, etc.
std::string foundName;
if (variateLibStem) {
foundName = lookupLibMaybeAddExt(libStem, RPath, RunPath, libLoader);
if (foundName.empty()) {
llvm::StringRef libStemName = llvm::sys::path::filename(libStem);
if (!libStemName.startswith("lib")) {
// try with "lib" prefix:
foundName = lookupLibMaybeAddExt(
libStem.str().insert(libStem.size()-libStemName.size(), "lib"),
RPath,
RunPath,
libLoader
);
}
}
} else {
foundName = lookupLibInPaths(libStem, RPath, RunPath, libLoader);
}
if (!foundName.empty() && isSharedLibrary(foundName))
if (!foundName.empty())
return platform::NormalizePath(foundName);
return std::string();
}
DynamicLibraryManager::LoadLibResult
DynamicLibraryManager::loadLibrary(const std::string& libStem,
DynamicLibraryManager::loadLibrary(llvm::StringRef libStem,
bool permanent, bool resolved) {
if (DEBUG > 7) {
cling::errs() << "Dyld::loadLibrary: " << libStem.str() << ", " <<
(permanent ? "permanent" : "not-permanent") << ", " <<
(resolved ? "resolved" : "not-resolved") << "\n";
}
std::string lResolved;
const std::string& canonicalLoadedLib = resolved ? libStem : lResolved;
const std::string& canonicalLoadedLib = resolved ? libStem.str() : lResolved;
if (!resolved) {
lResolved = lookupLibrary(libStem);
if (lResolved.empty())
@ -173,7 +373,7 @@ namespace cling {
if (!dyLibHandle) {
// We emit callback to LibraryLoadingFailed when we get error with error message.
if (InterpreterCallbacks* C = getCallbacks()) {
if (C->LibraryLoadingFailed(errMsg, libStem, permanent, resolved))
if (C->LibraryLoadingFailed(errMsg, libStem.str(), permanent, resolved))
return kLoadLibSuccess;
}
@ -248,6 +448,7 @@ namespace cling {
bool DynamicLibraryManager::isSharedLibrary(llvm::StringRef libFullPath,
bool* exists /*=0*/) {
using namespace llvm;
auto filetype = sys::fs::get_file_type(libFullPath, /*Follow*/ true);
if (filetype != sys::fs::file_type::regular_file) {
if (exists) {
@ -262,7 +463,7 @@ namespace cling {
if (exists)
*exists = !Error;
return !Error &&
bool result = !Error &&
#ifdef __APPLE__
(Magic == file_magic::macho_fixed_virtual_memory_shared_lib
|| Magic == file_magic::macho_dynamically_linked_shared_lib
@ -283,6 +484,8 @@ namespace cling {
# error "Unsupported platform."
#endif
;
return result;
}
} // end namespace cling

View File

@ -9,16 +9,26 @@
//------------------------------------------------------------------------------
#include "cling/Interpreter/DynamicLibraryManager.h"
#include "cling/Utils/Paths.h"
#include "cling/Utils/Platform.h"
#include "cling/Utils/Output.h"
#include "llvm/ADT/SmallSet.h"
#include "llvm/ADT/SmallString.h"
#include "llvm/ADT/StringRef.h"
#include "llvm/ADT/StringSet.h"
#include "llvm/ADT/StringMap.h"
#include "llvm/BinaryFormat/MachO.h"
#include "llvm/Object/COFF.h"
#include "llvm/Object/ELF.h"
#include "llvm/Object/ELFObjectFile.h"
#include "llvm/Object/MachO.h"
#include "llvm/Object/ObjectFile.h"
#include "llvm/Support/DynamicLibrary.h"
#include "llvm/Support/Error.h"
#include "llvm/Support/Path.h"
#include "llvm/Support/Program.h"
#include "llvm/Support/Format.h"
#include "llvm/Support/WithColor.h"
#include <algorithm>
#include <list>
@ -26,13 +36,18 @@
#include <unordered_set>
#include <vector>
#ifdef LLVM_ON_UNIX
#include <dlfcn.h>
#include <unistd.h>
#include <sys/stat.h>
#endif // LLVM_ON_UNIX
#ifdef __APPLE__
#include <mach-o/dyld.h>
#include <sys/stat.h>
#undef LC_LOAD_DYLIB
#undef LC_RPATH
#endif // __APPLE__
#ifdef _WIN32
@ -113,7 +128,6 @@ struct BloomFilter {
};
/// An efficient representation of a full path to a library which does not
/// duplicate common path patterns reducing the overall memory footprint.
///
@ -125,15 +139,12 @@ struct BloomFilter {
struct LibraryPath {
const BasePath& m_Path;
std::string m_LibName;
std::string m_FullName;
BloomFilter m_Filter;
llvm::StringSet<> m_Symbols;
//std::vector<const LibraryPath*> m_LibDeps;
LibraryPath(const BasePath& Path, const std::string& LibName)
: m_Path(Path), m_LibName(LibName) {
llvm::SmallString<512> Vec(m_Path);
llvm::sys::path::append(Vec, llvm::StringRef(m_LibName));
m_FullName = Vec.str().str();
}
bool operator==(const LibraryPath &other) const {
@ -141,8 +152,10 @@ struct LibraryPath {
m_LibName == other.m_LibName;
}
const std::string& GetFullName() const {
return m_FullName;
const std::string GetFullName() const {
llvm::SmallString<512> Vec(m_Path);
llvm::sys::path::append(Vec, llvm::StringRef(m_LibName));
return Vec.str().str();
}
void AddBloom(llvm::StringRef symbol) {
@ -204,10 +217,18 @@ public:
return m_LibsH.count(Lib);
}
void RegisterLib(const LibraryPath& Lib) {
const LibraryPath* GetRegisteredLib(const LibraryPath& Lib) const {
auto search = m_LibsH.find(Lib);
if (search != m_LibsH.end())
return &(*search);
return nullptr;
}
const LibraryPath* RegisterLib(const LibraryPath& Lib) {
auto it = m_LibsH.insert(Lib);
assert(it.second && "Already registered!");
m_Libs.push_back(&*it.first);
return &*it.first;
}
void UnregisterLib(const LibraryPath& Lib) {
@ -229,10 +250,155 @@ public:
}
};
static std::string getRealPath(llvm::StringRef path) {
llvm::SmallString<512> realPath;
llvm::sys::fs::real_path(path, realPath, /*expandTilde*/true);
return realPath.str().str();
#ifndef _WIN32
// Cached version of system function lstat
static inline mode_t cached_lstat(const char *path) {
static llvm::StringMap<mode_t> lstat_cache;
// If already cached - retun cached result
auto it = lstat_cache.find(path);
if (it != lstat_cache.end())
return it->second;
// If result not in cache - call system function and cache result
struct stat buf;
mode_t st_mode = (lstat(path, &buf) == -1) ? 0 : buf.st_mode;
lstat_cache.insert(std::pair<llvm::StringRef, mode_t>(path, st_mode));
return st_mode;
}
// Cached version of system function readlink
static inline llvm::StringRef cached_readlink(const char* pathname) {
static llvm::StringMap<std::string> readlink_cache;
// If already cached - retun cached result
auto it = readlink_cache.find(pathname);
if (it != readlink_cache.end())
return llvm::StringRef(it->second);
// If result not in cache - call system function and cache result
char buf[PATH_MAX] = "\0";
(void)readlink(pathname, buf, sizeof(buf));
std::string sym(buf);
readlink_cache.insert(std::pair<llvm::StringRef, std::string>(pathname, sym));
return readlink_cache[pathname];
}
#endif
// Cached version of system function realpath
std::string cached_realpath(llvm::StringRef path, llvm::StringRef base_path = "",
bool is_base_path_real = false,
long symlooplevel = 40) {
if (path.empty()) {
errno = ENOENT;
return "";
}
if (!symlooplevel) {
errno = ELOOP;
return "";
}
// If already cached - retun cached result
static llvm::StringMap<std::string> cache;
auto it = cache.find(path);
if (it != cache.end())
return it->second;
// If result not in cache - call system function and cache result
llvm::StringRef sep(llvm::sys::path::get_separator());
llvm::SmallString<256> result(sep);
#ifndef _WIN32
llvm::SmallVector<llvm::StringRef, 16> p;
// Relative or absolute path
if (llvm::sys::path::is_relative(path)) {
if (is_base_path_real) {
result.assign(base_path);
} else {
if (path[0] == '~' && (path.size() == 1 || llvm::sys::path::is_separator(path[1]))) {
static llvm::SmallString<128> home;
if (home.str().empty())
llvm::sys::path::home_directory(home);
llvm::StringRef(home).split(p, sep, /*MaxSplit*/ -1, /*KeepEmpty*/ false);
} else if (base_path.empty()) {
static llvm::SmallString<256> current_path;
if (current_path.str().empty())
llvm::sys::fs::current_path(current_path);
llvm::StringRef(current_path).split(p, sep, /*MaxSplit*/ -1, /*KeepEmpty*/ false);
} else {
base_path.split(p, sep, /*MaxSplit*/ -1, /*KeepEmpty*/ false);
}
}
}
path.split(p, sep, /*MaxSplit*/ -1, /*KeepEmpty*/ false);
// Handle path list items
for (auto item : p) {
if (item.startswith(".")) {
if (item == "..") {
size_t s = result.rfind(sep);
if (s != llvm::StringRef::npos) result.resize(s);
if (result.empty()) result = sep;
}
continue;
} else if (item == "~") {
continue;
}
size_t old_size = result.size();
llvm::sys::path::append(result, item);
mode_t st_mode = cached_lstat(result.c_str());
if (S_ISLNK(st_mode)) {
llvm::StringRef symlink = cached_readlink(result.c_str());
if (llvm::sys::path::is_relative(symlink)) {
result.set_size(old_size);
result = cached_realpath(symlink, result, true, symlooplevel - 1);
} else {
result = cached_realpath(symlink, "", true, symlooplevel - 1);
}
} else if (st_mode == 0) {
cache.insert(std::pair<llvm::StringRef, llvm::StringRef>(path, ""));
return "";
}
}
#else
llvm::sys::fs::real_path(path, result);
#endif
cache.insert(std::pair<llvm::StringRef, std::string>(path, result.str().str()));
return result.str().str();
}
using namespace llvm;
using namespace llvm::object;
template <class ELFT>
static Expected<StringRef> getDynamicStrTab(const ELFFile<ELFT>* Elf) {
auto DynamicEntriesOrError = Elf->dynamicEntries();
if (!DynamicEntriesOrError)
return DynamicEntriesOrError.takeError();
for (const typename ELFT::Dyn& Dyn : *DynamicEntriesOrError) {
if (Dyn.d_tag == ELF::DT_STRTAB) {
auto MappedAddrOrError = Elf->toMappedAddr(Dyn.getPtr());
if (!MappedAddrOrError)
return MappedAddrOrError.takeError();
return StringRef(reinterpret_cast<const char *>(*MappedAddrOrError));
}
}
// If the dynamic segment is not present, we fall back on the sections.
auto SectionsOrError = Elf->sections();
if (!SectionsOrError)
return SectionsOrError.takeError();
for (const typename ELFT::Shdr &Sec : *SectionsOrError) {
if (Sec.sh_type == ELF::SHT_DYNSYM)
return Elf->getStringTableForSymtab(Sec);
}
return createError("dynamic string table not found");
}
static llvm::StringRef GetGnuHashSection(llvm::object::ObjectFile *file) {
@ -256,7 +422,7 @@ static llvm::StringRef GetGnuHashSection(llvm::object::ObjectFile *file) {
///
///\returns true if the symbol may be in the library.
static bool MayExistInElfObjectFile(llvm::object::ObjectFile *soFile,
uint32_t hash) {
uint32_t hash) {
assert(soFile->isELF() && "Not ELF");
// Compute the platform bitness -- either 64 or 32.
@ -312,9 +478,9 @@ namespace cling {
/// complexity. It is tuned to compare BasePaths first by checking the
/// address and then the representation which models the base path reuse.
class BasePaths {
public:
std::unordered_set<BasePath, BasePathHashFunction,
BasePathEqFunction> m_Paths;
public:
const BasePath& RegisterBasePath(const std::string& Path,
bool* WasInserted = nullptr) {
@ -325,7 +491,7 @@ namespace cling {
return *it.first;
}
bool Contains (const std::string& Path) {
bool Contains(StringRef Path) {
return m_Paths.count(Path);
}
};
@ -346,7 +512,7 @@ namespace cling {
/// Contains a set of libraries which we gave to the user via ResolveSymbol
/// call and next time we should check if the user loaded them to avoid
/// useless iterations.
std::vector<LibraryPath> m_QueriedLibraries;
LibraryPaths m_QueriedLibraries;
using PermanentlyIgnoreCallbackProto = std::function<bool(llvm::StringRef)>;
const PermanentlyIgnoreCallbackProto m_ShouldPermanentlyIgnoreCallback;
@ -369,10 +535,11 @@ namespace cling {
///\param[in] mangledName - the mangled name to look for.
///\param[in] IgnoreSymbolFlags - The symbols to ignore upon a match.
///\returns true on success.
bool ContainsSymbol(const LibraryPath* Lib, const std::string &mangledName,
bool ContainsSymbol(const LibraryPath* Lib, StringRef mangledName,
unsigned IgnoreSymbolFlags = 0) const;
bool ShouldPermanentlyIgnore(const std::string& FileName) const;
bool ShouldPermanentlyIgnore(StringRef FileName) const;
void dumpDebugInfo() const;
public:
Dyld(const cling::DynamicLibraryManager &DLM,
PermanentlyIgnoreCallbackProto shouldIgnore,
@ -383,24 +550,73 @@ namespace cling {
~Dyld(){};
std::string searchLibrariesForSymbol(const std::string& mangledName,
std::string searchLibrariesForSymbol(StringRef mangledName,
bool searchSystem);
};
std::string RPathToStr(llvm::SmallVector<llvm::StringRef,2> V) {
std::string result;
for (auto item : V)
result += item.str() + ",";
if (!result.empty())
result.pop_back();
return result;
}
void CombinePaths(std::string& P1, const char* P2) {
if (!P2 || !P2[0]) return;
if (!P1.empty())
P1 += llvm::sys::EnvPathSeparator;
P1 += P2;
}
template <class ELFT>
void HandleDynTab(const ELFFile<ELFT>* Elf, llvm::StringRef FileName,
llvm::SmallVector<llvm::StringRef,2>& RPath,
llvm::SmallVector<llvm::StringRef,2>& RunPath,
std::vector<StringRef>& Deps) {
const char *Data = "";
if (Expected<StringRef> StrTabOrErr = getDynamicStrTab(Elf))
Data = StrTabOrErr.get().data();
auto DynamicEntriesOrError = Elf->dynamicEntries();
if (!DynamicEntriesOrError) {
cling::errs() << "Dyld: failed to read dynamic entries in"
<< "'" << FileName.str() << "'\n";
return;
}
for (const typename ELFT::Dyn& Dyn : *DynamicEntriesOrError) {
switch (Dyn.d_tag) {
case ELF::DT_NEEDED:
Deps.push_back(Data + Dyn.d_un.d_val);
break;
case ELF::DT_RPATH:
SplitPaths(Data + Dyn.d_un.d_val, RPath, utils::kAllowNonExistant, platform::kEnvDelim, false);
break;
case ELF::DT_RUNPATH:
SplitPaths(Data + Dyn.d_un.d_val, RunPath, utils::kAllowNonExistant, platform::kEnvDelim, false);
break;
// (Dyn.d_tag == ELF::DT_NULL) continue;
// (Dyn.d_tag == ELF::DT_AUXILIARY || Dyn.d_tag == ELF::DT_FILTER)
}
}
}
void Dyld::ScanForLibraries(bool searchSystemLibraries/* = false*/) {
// #ifndef NDEBUG
// if (!m_FirstRun && !m_FirstRunSysLib)
// assert(0 && "Already initialized");
// if (m_FirstRun && !m_Libraries->size())
// assert(0 && "Not initialized but m_Libraries is non-empty!");
// // assert((m_FirstRun || m_FirstRunSysLib) && (m_Libraries->size() ||
// m_SysLibraries.size())
// // && "Already scanned and initialized!");
// #endif
const auto &searchPaths = m_DynamicLibraryManager.getSearchPaths();
if (DEBUG > 7) {
cling::errs() << "Dyld::ScanForLibraries: system=" << (searchSystemLibraries?"true":"false") << "\n";
for (const DynamicLibraryManager::SearchPathInfo &Info : searchPaths)
cling::errs() << ">>>" << Info.Path << ", " << (Info.IsUser?"user\n":"system\n");
}
llvm::SmallSet<const BasePath*, 32> ScannedPaths;
for (const DynamicLibraryManager::SearchPathInfo &Info : searchPaths) {
if (Info.IsUser || searchSystemLibraries) {
if (Info.IsUser != searchSystemLibraries) {
// Examples which we should handle.
// File Real
// /lib/1/1.so /lib/1/1.so // file
@ -416,47 +632,182 @@ namespace cling {
// /lib/3/3.so
// /system/lib/1.so
//
// libL.so NEEDED/RPATH libR.so /lib/some-rpath/libR.so // needed/dependedt library in libL.so RPATH/RUNPATH or other (in)direct dep
//
// Paths = /lib/1 : /lib/2 : /lib/3
// m_BasePaths = ["/lib/1", "/lib/3", "/system/lib"]
// m_*Libraries = [<0,"1.so">, <1,"1.so">, <2,"s.so">, <1,"3.so">]
std::string RealPath = getRealPath(Info.Path);
if (DEBUG > 7) {
cling::errs() << "Dyld::ScanForLibraries Iter:" << Info.Path << " -> ";
}
std::string RealPath = cached_realpath(Info.Path);
llvm::StringRef DirPath(RealPath);
if (DEBUG > 7) {
cling::errs() << RealPath << "\n";
}
if (!llvm::sys::fs::is_directory(DirPath) || DirPath.empty())
continue;
// Already searched?
bool WasInserted;
m_BasePaths.RegisterBasePath(RealPath, &WasInserted);
if (!WasInserted)
const BasePath &ScannedBPath = m_BasePaths.RegisterBasePath(RealPath);
if (ScannedPaths.count(&ScannedBPath)) {
if (DEBUG > 7) {
cling::errs() << "Dyld::ScanForLibraries Already scanned: " << RealPath << "\n";
}
continue;
}
std::error_code EC;
for (llvm::sys::fs::directory_iterator DirIt(DirPath, EC), DirEnd;
DirIt != DirEnd && !EC; DirIt.increment(EC)) {
// FileName must be always full/absolute/resolved file name.
std::function<void(llvm::StringRef, unsigned)> HandleLib =
[&](llvm::StringRef FileName, unsigned level) {
// FIXME: Use a StringRef here!
std::string FileName = getRealPath(DirIt->path());
assert(!llvm::sys::fs::is_symlink_file(FileName));
if (DEBUG > 7) {
cling::errs() << "Dyld::ScanForLibraries HandleLib:" << FileName.str()
<< ", level=" << level << " -> ";
}
if (ShouldPermanentlyIgnore(FileName))
continue;
llvm::StringRef FileRealPath = llvm::sys::path::parent_path(FileName);
llvm::StringRef FileRealName = llvm::sys::path::filename(FileName);
const BasePath& BaseP = m_BasePaths.RegisterBasePath(FileRealPath.str());
LibraryPath LibPath(BaseP, FileRealName); //bp, str
std::string FileRealPath = llvm::sys::path::parent_path(FileName);
FileName = llvm::sys::path::filename(FileName);
const BasePath& BaseP = m_BasePaths.RegisterBasePath(FileRealPath);
LibraryPath LibPath(BaseP, FileName);
if (m_SysLibraries.HasRegisteredLib(LibPath) ||
m_Libraries.HasRegisteredLib(LibPath))
continue;
if (m_SysLibraries.GetRegisteredLib(LibPath) ||
m_Libraries.GetRegisteredLib(LibPath)) {
if (DEBUG > 7) {
cling::errs() << "Already handled!!!\n";
}
return;
}
if (ShouldPermanentlyIgnore(FileName)) {
if (DEBUG > 7) {
cling::errs() << "PermanentlyIgnored!!!\n";
}
return;
}
if (searchSystemLibraries)
m_SysLibraries.RegisterLib(LibPath);
else
m_Libraries.RegisterLib(LibPath);
// Handle lib dependencies
llvm::SmallVector<llvm::StringRef, 2> RPath;
llvm::SmallVector<llvm::StringRef, 2> RunPath;
std::vector<StringRef> Deps;
auto ObjFileOrErr =
llvm::object::ObjectFile::createObjectFile(FileName);
if (llvm::Error Err = ObjFileOrErr.takeError()) {
if (DEBUG > 1) {
std::string Message;
handleAllErrors(std::move(Err), [&](llvm::ErrorInfoBase &EIB) {
Message += EIB.message() + "; ";
});
cling::errs()
<< "Dyld::ScanForLibraries: Failed to read object file "
<< FileName.str() << " Errors: " << Message << "\n";
}
return;
}
llvm::object::ObjectFile *BinObjF = ObjFileOrErr.get().getBinary();
if (BinObjF->isELF()) {
if (const auto* ELF = dyn_cast<ELF32LEObjectFile>(BinObjF))
HandleDynTab(ELF->getELFFile(), FileName, RPath, RunPath, Deps);
else if (const auto* ELF = dyn_cast<ELF32BEObjectFile>(BinObjF))
HandleDynTab(ELF->getELFFile(), FileName, RPath, RunPath, Deps);
else if (const auto* ELF = dyn_cast<ELF64LEObjectFile>(BinObjF))
HandleDynTab(ELF->getELFFile(), FileName, RPath, RunPath, Deps);
else if (const auto* ELF = dyn_cast<ELF64BEObjectFile>(BinObjF))
HandleDynTab(ELF->getELFFile(), FileName, RPath, RunPath, Deps);
} else if (BinObjF->isMachO()) {
MachOObjectFile *Obj = (MachOObjectFile*)BinObjF;
for (const auto &Command : Obj->load_commands()) {
if (Command.C.cmd == MachO::LC_LOAD_DYLIB) {
//Command.C.cmd == MachO::LC_ID_DYLIB ||
//Command.C.cmd == MachO::LC_LOAD_WEAK_DYLIB ||
//Command.C.cmd == MachO::LC_REEXPORT_DYLIB ||
//Command.C.cmd == MachO::LC_LAZY_LOAD_DYLIB ||
//Command.C.cmd == MachO::LC_LOAD_UPWARD_DYLIB ||
MachO::dylib_command dylibCmd =
Obj->getDylibIDLoadCommand(Command);
Deps.push_back(StringRef(Command.Ptr + dylibCmd.dylib.name));
}
else if (Command.C.cmd == MachO::LC_RPATH) {
MachO::rpath_command rpathCmd = Obj->getRpathCommand(Command);
SplitPaths(Command.Ptr + rpathCmd.path, RPath, utils::kAllowNonExistant, platform::kEnvDelim, false);
}
}
} else if (BinObjF->isCOFF()) {
// TODO: COFF support
}
if (DEBUG > 7) {
cling::errs() << "Dyld::ScanForLibraries: Deps Info:\n";
cling::errs() << "Dyld::ScanForLibraries: RPATH=" << RPathToStr(RPath) << "\n";
cling::errs() << "Dyld::ScanForLibraries: RUNPATH=" << RPathToStr(RunPath) << "\n";
int x = 0;
for (StringRef dep : Deps)
cling::errs() << "Dyld::ScanForLibraries: Deps[" << x++ << "]=" << dep.str() << "\n";
}
// Heuristics for workaround performance problems:
// (H1) If RPATH and RUNPATH == "" -> skip handling Deps
if (RPath.empty() && RunPath.empty()) {
if (DEBUG > 7) {
cling::errs() << "Dyld::ScanForLibraries: Skip all deps by Heuristic1: " << FileName.str() << "\n";
}
return;
};
// (H2) If RPATH subset of LD_LIBRARY_PATH &&
// RUNPATH subset of LD_LIBRARY_PATH -> skip handling Deps
if (std::all_of(RPath.begin(), RPath.end(), [&](StringRef item){ return std::any_of(searchPaths.begin(), searchPaths.end(), [&](DynamicLibraryManager::SearchPathInfo item1){ return item==item1.Path; }); }) &&
std::all_of(RunPath.begin(), RunPath.end(), [&](StringRef item){ return std::any_of(searchPaths.begin(), searchPaths.end(), [&](DynamicLibraryManager::SearchPathInfo item1){ return item==item1.Path; }); }) ) {
if (DEBUG > 7) {
cling::errs() << "Dyld::ScanForLibraries: Skip all deps by Heuristic2: " << FileName.str() << "\n";
}
return;
}
// Handle dependencies
for (StringRef dep : Deps) {
std::string dep_full =
m_DynamicLibraryManager.lookupLibrary(dep, RPath, RunPath, FileName, false);
HandleLib(dep_full, level + 1);
}
};
if (DEBUG > 7) {
cling::errs() << "Dyld::ScanForLibraries: Iterator: " << DirPath << "\n";
}
std::error_code EC;
for (llvm::sys::fs::directory_iterator DirIt(DirPath, EC), DirEnd;
DirIt != DirEnd && !EC; DirIt.increment(EC)) {
if (DEBUG > 7) {
cling::errs() << "Dyld::ScanForLibraries: Iterator >>> " <<
DirIt->path() << ", type=" << (short)(DirIt->type()) << "\n";
}
const llvm::sys::fs::file_type ft = DirIt->type();
if (ft == llvm::sys::fs::file_type::regular_file) {
HandleLib(DirIt->path(), 0);
} else if (ft == llvm::sys::fs::file_type::symlink_file) {
std::string DepFileName_str = cached_realpath(DirIt->path());
llvm::StringRef DepFileName = DepFileName_str;
assert(!llvm::sys::fs::is_symlink_file(DepFileName));
if (!llvm::sys::fs::is_directory(DepFileName))
HandleLib(DepFileName, 0);
}
}
// Register the DirPath as fully scanned.
ScannedPaths.insert(&ScannedBPath);
}
}
}
@ -470,6 +821,11 @@ namespace cling {
using namespace llvm;
using namespace llvm::object;
if (DEBUG > 7) {
cling::errs()<< "Dyld::BuildBloomFilter: Start building Bloom filter for: "
<< Lib->GetFullName() << "\n";
}
// If BloomFilter is empty then build it.
// Count Symbols and generate BloomFilter
uint32_t SymbolsCount = 0;
@ -580,14 +936,14 @@ namespace cling {
}
bool Dyld::ContainsSymbol(const LibraryPath* Lib,
const std::string &mangledName,
StringRef mangledName,
unsigned IgnoreSymbolFlags /*= 0*/) const {
const std::string library_filename = Lib->GetFullName();
if (DEBUG > 7) {
cling::errs() << "Dyld::ContainsSymbol: Find symbol: lib="
<< library_filename << ", mangled="
<< mangledName << "\n";
<< mangledName.str() << "\n";
}
auto ObjF = llvm::object::ObjectFile::createObjectFile(library_filename);
@ -609,8 +965,11 @@ namespace cling {
// Check for the gnu.hash section if ELF.
// If the symbol doesn't exist, exit early.
if (BinObjFile->isELF() &&
!MayExistInElfObjectFile(BinObjFile, hashedMangle))
!MayExistInElfObjectFile(BinObjFile, hashedMangle)) {
if (DEBUG > 7)
cling::errs() << "Dyld::ContainsSymbol: ELF BloomFilter: Skip symbol <" << mangledName.str() << ">.\n";
return false;
}
if (m_UseBloomFilter) {
// Use our bloom filters and create them if necessary.
@ -621,12 +980,12 @@ namespace cling {
// If the symbol does not exist, exit early. In case it may exist, iterate.
if (!Lib->MayExistSymbol(hashedMangle)) {
if (DEBUG > 7)
cling::errs() << "Dyld::ContainsSymbol: BloomFilter: Skip symbol.\n";
cling::errs() << "Dyld::ContainsSymbol: BloomFilter: Skip symbol <" << mangledName.str() << ">.\n";
return false;
}
if (DEBUG > 7)
cling::errs() << "Dyld::ContainsSymbol: BloomFilter: Symbol May exist."
<< " Search for it.";
cling::errs() << "Dyld::ContainsSymbol: BloomFilter: Symbol <" << mangledName.str() << "> May exist."
<< " Search for it. ";
}
if (m_UseHashTable) {
@ -658,7 +1017,7 @@ namespace cling {
llvm::Expected<llvm::StringRef> SymNameErr = S.getName();
if (!SymNameErr) {
cling::errs() << "Dyld::ContainsSymbol: Failed to read symbol "
<< mangledName << "\n";
<< mangledName.str() << "\n";
continue;
}
@ -668,7 +1027,7 @@ namespace cling {
if (SymNameErr.get() == mangledName) {
if (DEBUG > 1) {
cling::errs() << "Dyld::ContainsSymbol: Symbol "
<< mangledName << " found in "
<< mangledName.str() << " found in "
<< library_filename << "\n";
return true;
}
@ -680,34 +1039,44 @@ namespace cling {
// If no hash symbol then iterate to detect symbol
// We Iterate only if BloomFilter and/or SymbolHashTable are not supported.
if (DEBUG > 7)
cling::errs() << "Dyld::ContainsSymbol: Iterate all for <"
<< mangledName.str() << ">";
// Symbol may exist. Iterate.
if (ForeachSymbol(BinObjFile->symbols(), IgnoreSymbolFlags, mangledName))
if (ForeachSymbol(BinObjFile->symbols(), IgnoreSymbolFlags, mangledName)) {
if (DEBUG > 7)
cling::errs() << " -> found.\n";
return true;
}
if (!BinObjFile->isELF())
if (!BinObjFile->isELF()) {
if (DEBUG > 7)
cling::errs() << " -> not found.\n";
return false;
}
// ELF file format has .dynstr section for the dynamic symbol table.
const auto *ElfObj =
llvm::cast<llvm::object::ELFObjectFileBase>(BinObjFile);
return ForeachSymbol(ElfObj->getDynamicSymbolIterators(),
IgnoreSymbolFlags, mangledName);
bool result = ForeachSymbol(ElfObj->getDynamicSymbolIterators(),
IgnoreSymbolFlags, mangledName);
if (DEBUG > 7)
cling::errs() << (result ? " -> found.\n" : " -> not found.\n");
return result;
}
bool Dyld::ShouldPermanentlyIgnore(const std::string& FileName) const {
bool Dyld::ShouldPermanentlyIgnore(StringRef FileName) const {
assert(!m_ExecutableFormat.empty() && "Failed to find the object format!");
if (llvm::sys::fs::is_directory(FileName))
return true;
if (!cling::DynamicLibraryManager::isSharedLibrary(FileName))
return true;
// No need to check linked libraries, as this function is only invoked
// for symbols that cannot be found (neither by dlsym nor in the JIT).
if (m_DynamicLibraryManager.isLibraryLoaded(FileName.c_str()))
if (m_DynamicLibraryManager.isLibraryLoaded(FileName))
return true;
@ -754,20 +1123,59 @@ namespace cling {
return m_ShouldPermanentlyIgnoreCallback(FileName);
}
std::string Dyld::searchLibrariesForSymbol(const std::string& mangledName,
void Dyld::dumpDebugInfo() const {
cling::errs() << "Dyld: m_BasePaths:\n";
cling::errs() << "---\n";
size_t x = 0;
for (auto const &item : m_BasePaths.m_Paths) {
cling::errs() << "Dyld: - m_BasePaths[" << x++ << "]:"
<< &item << ": " << item << "\n";
}
cling::errs() << "---\n";
x = 0;
for (auto const &item : m_Libraries.GetLibraries()) {
cling::errs() << "Dyld: - m_Libraries[" << x++ << "]:"
<< &item << ": " << item->m_Path << ", "
<< item->m_LibName << "\n";
}
x = 0;
for (auto const &item : m_SysLibraries.GetLibraries()) {
cling::errs() << "Dyld: - m_SysLibraries[" << x++ << "]:"
<< &item << ": " << item->m_Path << ", "
<< item->m_LibName << "\n";
}
}
std::string Dyld::searchLibrariesForSymbol(StringRef mangledName,
bool searchSystem/* = true*/) {
assert(!llvm::sys::DynamicLibrary::SearchForAddressOfSymbol(mangledName) &&
"Library already loaded, please use dlsym!");
assert(!mangledName.empty());
using namespace llvm::sys::path;
using namespace llvm::sys::fs;
if (m_FirstRun) {
if (DEBUG > 7) {
cling::errs() << "Dyld::searchLibrariesForSymbol:" << mangledName.str() <<
", searchSystem=" << (searchSystem ? "true" : "false") << ", FirstRun(user)... scanning\n";
}
if (DEBUG > 7) {
cling::errs() << "Dyld::searchLibrariesForSymbol: Before first ScanForLibraries\n";
dumpDebugInfo();
}
ScanForLibraries(/* SearchSystemLibraries= */ false);
m_FirstRun = false;
if (DEBUG > 7) {
cling::errs() << "Dyld::searchLibrariesForSymbol: After first ScanForLibraries\n";
dumpDebugInfo();
}
}
if (!m_QueriedLibraries.empty()) {
if (m_QueriedLibraries.size() > 0) {
// Last call we were asked if a library contains a symbol. Usually, the
// caller wants to load this library. Check if was loaded and remove it
// from our lists of not-yet-loaded libs.
@ -775,31 +1183,35 @@ namespace cling {
if (DEBUG > 7) {
cling::errs() << "Dyld::ResolveSymbol: m_QueriedLibraries:\n";
size_t x = 0;
for (auto item : m_QueriedLibraries) {
for (auto item : m_QueriedLibraries.GetLibraries()) {
cling::errs() << "Dyld::ResolveSymbol - [" << x++ << "]:"
<< &item << ": " << item.m_Path << ", "
<< item.m_LibName << "\n";
<< &item << ": " << item->GetFullName() << "\n";
}
}
for (const LibraryPath& P : m_QueriedLibraries) {
const std::string LibName = P.GetFullName();
for (const LibraryPath* P : m_QueriedLibraries.GetLibraries()) {
const std::string LibName = P->GetFullName();
if (!m_DynamicLibraryManager.isLibraryLoaded(LibName))
continue;
m_Libraries.UnregisterLib(P);
m_SysLibraries.UnregisterLib(P);
m_Libraries.UnregisterLib(*P);
m_SysLibraries.UnregisterLib(*P);
}
// TODO: m_QueriedLibraries.clear ?
}
// Iterate over files under this path. We want to get each ".so" files
for (const LibraryPath* P : m_Libraries.GetLibraries()) {
const std::string LibName = P->GetFullName();
if (ContainsSymbol(P, mangledName, /*ignore*/
llvm::object::SymbolRef::SF_Undefined)) {
m_QueriedLibraries.push_back(*P);
return LibName;
if (!m_QueriedLibraries.HasRegisteredLib(*P))
m_QueriedLibraries.RegisterLib(*P);
if (DEBUG > 7)
cling::errs() << "Dyld::ResolveSymbol: Search found match in [user lib]: "
<< P->GetFullName() << "!\n";
return P->GetFullName();
}
}
@ -807,59 +1219,47 @@ namespace cling {
return "";
if (DEBUG > 7)
cling::errs() << "Dyld::ResolveSymbol: SearchSystem!\n";
cling::errs() << "Dyld::searchLibrariesForSymbol: SearchSystem!!!\n";
// Lookup in non-system libraries failed. Expand the search to the system.
if (m_FirstRunSysLib) {
if (DEBUG > 7) {
cling::errs() << "Dyld::searchLibrariesForSymbol:" << mangledName.str() <<
", searchSystem=" << (searchSystem ? "true" : "false") << ", FirstRun(system)... scanning\n";
}
if (DEBUG > 7) {
cling::errs() << "Dyld::searchLibrariesForSymbol: Before first system ScanForLibraries\n";
dumpDebugInfo();
}
ScanForLibraries(/* SearchSystemLibraries= */ true);
m_FirstRunSysLib = false;
if (DEBUG > 7) {
cling::errs() << "Dyld::searchLibrariesForSymbol: After first system ScanForLibraries\n";
dumpDebugInfo();
}
}
for (const LibraryPath* P : m_SysLibraries.GetLibraries()) {
const std::string LibName = P->GetFullName();
if (ContainsSymbol(P, mangledName, /*ignore*/
llvm::object::SymbolRef::SF_Undefined |
llvm::object::SymbolRef::SF_Weak)) {
m_QueriedLibraries.push_back(*P);
return LibName;
if (!m_QueriedLibraries.HasRegisteredLib(*P))
m_QueriedLibraries.RegisterLib(*P);
if (DEBUG > 7)
cling::errs() << "Dyld::ResolveSymbol: Search found match in [system lib]: "
<< P->GetFullName() << "!\n";
return P->GetFullName();
}
}
if (DEBUG > 7)
cling::errs() << "Dyld::ResolveSymbol: Search found no match!\n";
/*
if (DEBUG > 7) {
cling::errs() << "Dyld::ResolveSymbol: Structs after ResolveSymbol:\n");
cling::errs() << "Dyld::ResolveSymbol - sPaths:\n");
size_t x = 0;
for (const auto &item : sPaths.GetPaths())
cling::errs() << "Dyld::ResolveSymbol << [" x++ << "]: " << item << "\n";
cling::errs() << "Dyld::ResolveSymbol - sLibs:\n");
x = 0;
for (const auto &item : sLibraries.GetLibraries())
cling::errs() << "Dyld::ResolveSymbol ["
<< x++ << "]: " << item->Path << ", "
<< item->LibName << "\n";
cling::errs() << "Dyld::ResolveSymbol - sSysLibs:");
x = 0;
for (const auto &item : sSysLibraries.GetLibraries())
cling::errs() << "Dyld::ResolveSymbol ["
<< x++ << "]: " << item->Path << ", "
<< item->LibName << "\n";
Info("Dyld::ResolveSymbol", "- sQueriedLibs:");
x = 0;
for (const auto &item : sQueriedLibraries)
cling::errs() << "Dyld::ResolveSymbol ["
<< x++ << "]: " << item->Path << ", "
<< item->LibName << "\n";
}
*/
return ""; // Search found no match.
}
@ -883,7 +1283,7 @@ namespace cling {
}
std::string
DynamicLibraryManager::searchLibrariesForSymbol(const std::string& mangledName,
DynamicLibraryManager::searchLibrariesForSymbol(StringRef mangledName,
bool searchSystem/* = true*/) const {
assert(m_Dyld && "Must call initialize dyld before!");
return m_Dyld->searchLibrariesForSymbol(mangledName, searchSystem);
@ -903,7 +1303,8 @@ namespace cling {
if (!GetModuleFileNameA (hMod, moduleName, sizeof (moduleName)))
return {};
return getRealPath(moduleName);
return cached_realpath(moduleName);
#else
// assume we have defined HAVE_DLFCN_H and HAVE_DLADDR
Dl_info info;
@ -912,7 +1313,8 @@ namespace cling {
return {};
} else {
if (strchr(info.dli_fname, '/'))
return getRealPath(info.dli_fname);
return cached_realpath(info.dli_fname);
// Else absolute path. For all we know that's a binary.
// Some people have dictionaries in binaries, this is how we find their
// path: (see also https://stackoverflow.com/a/1024937/6182509)
@ -920,23 +1322,23 @@ namespace cling {
char buf[PATH_MAX] = { 0 };
uint32_t bufsize = sizeof(buf);
if (_NSGetExecutablePath(buf, &bufsize) >= 0)
return getRealPath(buf);
return getRealPath(info.dli_fname);
return cached_realpath(buf);
return cached_realpath(info.dli_fname);
# elif defined(LLVM_ON_UNIX)
char buf[PATH_MAX] = { 0 };
// Cross our fingers that /proc/self/exe exists.
if (readlink("/proc/self/exe", buf, sizeof(buf)) > 0)
return getRealPath(buf);
return cached_realpath(buf);
std::string pipeCmd = std::string("which \"") + info.dli_fname + "\"";
FILE* pipe = popen(pipeCmd.c_str(), "r");
if (!pipe)
return getRealPath(info.dli_fname);
return cached_realpath(info.dli_fname);
std::string result;
while (fgets(buf, sizeof(buf), pipe))
result += buf;
pclose(pipe);
return getRealPath(result);
return cached_realpath(result);
# else
# error "Unsupported platform."
# endif

View File

@ -0,0 +1,22 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib.c -o%t-dir/lib/libcall_lib%shlibext
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library call_lib. Lookup functions from libraries and
// use them to print result value.
.L libcall_lib
extern "C" int cling_testlibrary_function();
int i = cling_testlibrary_function();
extern "C" int printf(const char* fmt, ...);
printf("got i=%d\n", i); // CHECK: got i=42
.q

View File

@ -0,0 +1,13 @@
/*------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//----------------------------------------------------------------------------*/
// RUN: true
// Used as library source by call.C, etc.
CLING_EXPORT int cling_testlibrary_function() {
return 42;
}

View File

@ -0,0 +1,13 @@
/*------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//----------------------------------------------------------------------------*/
// RUN: true
// Used as library source by callable_lib_A.C
CLING_EXPORT int cling_testlibrary_function_A() {
return 0xAA;
}

View File

@ -0,0 +1,13 @@
/*------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//----------------------------------------------------------------------------*/
// RUN: true
// Used as library source by callable_lib_AA.C, etc.
CLING_EXPORT int cling_testlibrary_function_A() {
return 0xAAAA;
}

View File

@ -0,0 +1,13 @@
/*------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//----------------------------------------------------------------------------*/
// RUN: true
// Used as library source by callable_lib_B.C
CLING_EXPORT int cling_testlibrary_function_B() {
return 0xBB;
}

View File

@ -0,0 +1,13 @@
/*------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//----------------------------------------------------------------------------*/
// RUN: true
// Used as library source by callable_lib_BB.C, etc.
CLING_EXPORT int cling_testlibrary_function_B() {
return 0xBBBB;
}

View File

@ -0,0 +1,13 @@
/*------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//----------------------------------------------------------------------------*/
// RUN: true
// Used as library source by callable_lib_L.C
CLING_EXPORT int cling_testlibrary_function() {
return 88;
}

View File

@ -0,0 +1,15 @@
/*------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//----------------------------------------------------------------------------*/
// RUN: true
// Used as library source by callale_lib_L3.C, etc.
extern int cling_testlibrary_function();
CLING_EXPORT int cling_testlibrary_function3() {
return cling_testlibrary_function() + 3;
}

View File

@ -0,0 +1,16 @@
/*------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//----------------------------------------------------------------------------*/
// RUN: true
// Used as library source by callale_lib_L_AB.C, etc.
extern int cling_testlibrary_function_A();
extern int cling_testlibrary_function_B();
CLING_EXPORT int cling_testlibrary_function() {
return cling_testlibrary_function_A() + cling_testlibrary_function_B();
}

View File

@ -0,0 +1,21 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib.c -o%t-dir/lib/libcall_lib%shlibext
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library call_lib. Lookup function and use it to print
// result value.
.L libcall_lib
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: (int) 42
.q

View File

@ -0,0 +1,21 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/lib/libcall_lib_A%shlibext
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_A. Lookup function and use it to print
// result value.
.L libcall_lib_A
extern "C" int cling_testlibrary_function_A();
cling_testlibrary_function_A()
// CHECK: (int) 170
.q

View File

@ -0,0 +1,22 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_AA.c -o%t-dir/lib/libcall_lib_A%shlibext
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_A. Lookup function and use it to print
// result value. This value is diffrerent from another Lib_A variants
// becouse this library is used for test library loading order.
.L libcall_lib_A
extern "C" int cling_testlibrary_function_A();
cling_testlibrary_function_A()
// CHECK: (int) 43690
.q

View File

@ -0,0 +1,21 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/lib/libcall_lib_B%shlibext
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_B. Lookup function and use it to print
// result value.
.L libcall_lib_B
extern "C" int cling_testlibrary_function_B();
cling_testlibrary_function_B()
// CHECK: (int) 187
.q

View File

@ -0,0 +1,22 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_BB.c -o%t-dir/lib/libcall_lib_B%shlibext
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_B. Lookup function and use it to print
// result value. This value is diffrerent from another Lib_B variants
// because this library is used for test library loading order.
.L libcall_lib_B
extern "C" int cling_testlibrary_function_B();
cling_testlibrary_function_B()
// CHECK: (int) 48059
.q

View File

@ -0,0 +1,21 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_L.c -o%t-dir/lib/libcall_lib_L%shlibext
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L. Lookup function and use it to print
// result value.
.L libcall_lib_L
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: (int) 88
.q

View File

@ -0,0 +1,50 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: mkdir -p %t-dir/lib3
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,--disable-new-dtags -Wl,-rpath,%t-dir/rlib -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: %clang %fPIC -shared -Wl,--disable-new-dtags -Wl,-rpath,%t-dir/lib -DCLING_EXPORT=%dllexport %S/call_lib_L3.c -o%t-dir/lib3/libcall_lib_L3%shlibext -L %t-dir/lib -lcall_lib_L_AB
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/lib3" %cling 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L3 that depends on Lib_L_AB that depends on
// two libraries Lib_A and Lib_B thru RPATH. Lib_L_AB, Lib_A and Lib_B are
// not in LD_LIBRARY_PATH and are reachable only thru RPATHs.
// This test try to lookup libraries and function in Lib_L3.
extern "C" int cling_testlibrary_function3();
cling_testlibrary_function3()
// CHECK: {{.*}}libcall_lib_L3{{.*}}
.L libcall_lib_L3
cling_testlibrary_function3()
// CHECK: (int) 360
// Test: Lookup and load library Lib_L3 that depends on Lib_L_AB that depends on
// two libraries Lib_A and Lib_B thru RPATH. Lib_L_AB, Lib_A and Lib_B are
// not in LD_LIBRARY_PATH and are reachable only thru RPATHs.
// This test try to lookup libraries and function in second level library
// Lib_L_AB.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: (int) 357
// Test: Lookup and load library Lib_L3 that depends on Lib_L_AB that depends on
// two libraries Lib_A and Lib_B thru RPATH. Lib_L_AB, Lib_A and Lib_B are
// not in LD_LIBRARY_PATH and are reachable only thru RPATHs.
// This test try to lookup libraries and function in third level library
// Lib_A.
extern "C" int cling_testlibrary_function_A();
cling_testlibrary_function_A()
// CHECK: (int) 170
.q

View File

@ -0,0 +1,50 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: mkdir -p %t-dir/lib3
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,-rpath,%t-dir/rlib -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: %clang %fPIC -shared -Wl,-rpath,%t-dir/lib -DCLING_EXPORT=%dllexport %S/call_lib_L3.c -o%t-dir/lib3/libcall_lib_L3%shlibext -L %t-dir/lib -lcall_lib_L_AB
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/lib3" %cling 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L3 that depends on Lib_L_AB that depends on
// two libraries Lib_A and Lib_B thru RPATH. Lib_L_AB, Lib_A and Lib_B are
// not in LD_LIBRARY_PATH and are reachable only thru RUNPATHs.
// This test try to lookup libraries and function in Lib_L3.
extern "C" int cling_testlibrary_function3();
cling_testlibrary_function3()
// CHECK: {{.*}}libcall_lib_L3{{.*}}
.L libcall_lib_L3
cling_testlibrary_function3()
// CHECK: (int) 360
// Test: Lookup and load library Lib_L3 that depends on Lib_L_AB that depends on
// two libraries Lib_A and Lib_B thru RPATH. Lib_L_AB, Lib_A and Lib_B are
// not in LD_LIBRARY_PATH and are reachable only thru RUNPATHs.
// This test try to lookup libraries and function in second level library
// Lib_L_AB.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: (int) 357
// Test: Lookup and load library Lib_L3 that depends on Lib_L_AB that depends on
// two libraries Lib_A and Lib_B thru RPATH. Lib_L_AB, Lib_A and Lib_B are
// not in LD_LIBRARY_PATH and are reachable only thru RUNPATHs.
// This test try to lookup libraries and function in third level library
// Lib_A.
extern "C" int cling_testlibrary_function_A();
cling_testlibrary_function_A()
// CHECK: (int) 170
.q

View File

@ -0,0 +1,35 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -l%t-dir/rlib/libcall_lib_A.so -l%t-dir/rlib/libcall_lib_B.so
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B thru absolute file names. Lib_A and Lib_B are outside
// library loading path.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
// Test: Second level library symbol lookup. Lookup function in Lib_A and print
// result value. LibA is not in loading path and symbols are reachable only via
// Lib_AB.
extern "C" int cling_testlibrary_function_A();
cling_testlibrary_function_A()
// CHECK: (int) 170
.q

View File

@ -0,0 +1,27 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// REQUIRES: shell
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/rlib" %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via file names. Lib_A and Lib_B are also in LD_LIBRARY_PATH.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,25 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/lib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/lib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/lib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/lib" %cling 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via file names. Lib_L_AB, Lib_A and Lib_B are in LD_LIBRARY_PATH.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,30 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib1
// RUN: mkdir -p %t-dir/rlib2
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib1/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib1/libcall_lib_B%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_AA.c -o%t-dir/rlib2/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_BB.c -o%t-dir/rlib2/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,--disable-new-dtags -Wl,-rpath,%t-dir/rlib1 -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib1 -lcall_lib_A -lcall_lib_B
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/lib:%t-dir/rlib2" %cling 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RPATH. Lib_A and Lib_B are also in LD_LIBRARY_PATH.
// Lib_L_AB must load and use libraries in RPATH first.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,31 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib1
// RUN: mkdir -p %t-dir/rlib2
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib1/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib1/libcall_lib_B%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_AA.c -o%t-dir/rlib2/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_BB.c -o%t-dir/rlib2/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,-rpath,%t-dir/rlib1 -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib1 -lcall_lib_A -lcall_lib_B
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/lib:%t-dir/rlib2" %cling 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RUNPATH. Lib_A and Lib_B are also in LD_LIBRARY_PATH.
// Lib_L_AB must load and use libraries in LD_LIBRARY_PATH first.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 91749
357
.q

View File

@ -0,0 +1,27 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/lib:%t-dir/rlib" %cling 2>&1 | FileCheck %s
// Test: Lookup function in libraries and found containing library Lib_L_AB.
// Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B. Lib_A and Lib_B are in LD_LIBRARY_PATH.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,25 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/lib:%t-dir/rlib" %cling 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RPATH. Lib_A and Lib_B are also in LD_LIBRARY_PATH.
// Lib_L_AB must load and use libraries in RPATH first.
.L libcall_lib_L_AB
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,26 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/lib:%t-dir/rlib" %cling 2>&1 | FileCheck %s
// Test: Lookup and load libraries Lib_A, Lib_B and Lib_L_AB that depends on two
// libraries Lib_A and Lib_B. Lib_A and Lib_B are also in LD_LIBRARY_PATH.
.L libcall_lib_A
.L libcall_lib_B
.L libcall_lib_L_AB
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,26 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,--disable-new-dtags -Wl,-rpath,%t-dir/rlib -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RPATH. Lib_A and Lib_B are not in LD_LIBRARY_PATH.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,28 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib1
// RUN: mkdir -p %t-dir/rlib2
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib1/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib2/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,--disable-new-dtags -Wl,-rpath,%t-dir/rlib1 -Wl,-rpath,%t-dir/rlib2 -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib1 -L %t-dir/rlib2 -lcall_lib_A -lcall_lib_B
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RPATH. Lib_A and Lib_B in two different directories
// and are not in LD_LIBRARY_PATH.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,26 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,-rpath,%t-dir/rlib -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RUNPATH. Lib_A and Lib_B are not in LD_LIBRARY_PATH.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,28 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/rlib1
// RUN: mkdir -p %t-dir/rlib2
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib1/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib2/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,-rpath,%t-dir/rlib1 -Wl,-rpath,%t-dir/rlib2 -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib1 -L %t-dir/rlib2 -lcall_lib_A -lcall_lib_B
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RPATH. Lib_A and Lib_B are in two different directories
// and are not in LD_LIBRARY_PATH.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,28 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// UNSUPPORTED: macos
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,-rpath,'$ORIGIN/../rlib' -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RUNPATH. Lib_A and Lib_B are not in LD_LIBRARY_PATH.
// RUNPATH use substitution to $ORIGIN.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,28 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// UNSUPPORTED: windows, linux
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,-rpath,'@executable_path/../tools/cling/test/DynamicLibraryManager/Output/%basename_t.tmp-dir/rlib' -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RUNPATH. Lib_A and Lib_B are not in LD_LIBRARY_PATH.
// RUNPATH use substitution to @executable_path.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,28 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// UNSUPPORTED: windows, linux
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,-rpath,'@loader_path/../rlib' -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RUNPATH. Lib_A and Lib_B are not in LD_LIBRARY_PATH.
// RUNPATH use substitution to @loader_path.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,28 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// UNSUPPORTED: windows
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,-rpath,'%t-dir/rlib' -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RUNPATH. Lib_A and Lib_B are not in LD_LIBRARY_PATH.
// RUNPATH does not use substitution and path is absolute.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,28 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// UNSUPPORTED: windows
// RUN: mkdir -p %t-dir/rlib
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/rlib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/rlib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -Wl,--disable-new-dtags -Wl,-rpath,'%t-dir/rlib' -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/rlib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | %cling -L%t-dir/lib 2>&1 | FileCheck %s
// Test: Lookup and load library Lib_L_AB that depends on two libraries Lib_A
// and Lib_B via RPATH. Lib_A and Lib_B are not in LD_LIBRARY_PATH.
// RPATH does not use substitution and path is absolute.
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: {{.*}}libcall_lib_L_AB{{.*}}
.L libcall_lib_L_AB
cling_testlibrary_function()
// CHECK: (int) 357
.q

View File

@ -0,0 +1,19 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// REQUIRES: shell
// RUN: env -i LD_LIBRARY_PATH="../:./../" %cling ".L" 2>&1 | FileCheck %s
// Test: Cling must use (DY)LD_LIBRARY_PATH as path for search libraries.
// CHECK: ../
// CHECK-NEXT: ./../
// CHECK-NEXT: .
// CHECK-NEXT: [system]
.q

View File

@ -0,0 +1,27 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib.c -o%t-dir/lib/libcall_lib%shlibext
// RUN: cat %s | %cling -L %t-dir/lib 2>&1 | FileCheck %s
// Test: Cling pragma for loading libraries. Cling shows error when library
// do not exists (do not reacheble via library PATH.
#pragma cling load("DoesNotExistPleaseRecover")
// expected-error@input_line_13:1{{'DoesNotExistPleaseRecover' file not found}}
// Test: Cling pragma for loading libraries. Lookup and load library call_lib.
// Lookup functions from libraries and use them to print result value.
#pragma cling load("libcall_lib")
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: (int) 42
.q

View File

@ -0,0 +1,25 @@
//------------------------------------------------------------------------------
// CLING - the C++ LLVM-based InterpreterG :)
//
// This file is dual-licensed: you can choose to license it under the University
// of Illinois Open Source License or the GNU Lesser General Public License. See
// LICENSE.TXT for details.
//------------------------------------------------------------------------------
// RUN: mkdir -p %t-dir/lib
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_A.c -o%t-dir/lib/libcall_lib_A%shlibext
// RUN: %clang -shared -DCLING_EXPORT=%dllexport %S/call_lib_B.c -o%t-dir/lib/libcall_lib_B%shlibext
// RUN: %clang %fPIC -shared -DCLING_EXPORT=%dllexport %S/call_lib_L_AB.c -o%t-dir/lib/libcall_lib_L_AB%shlibext -L %t-dir/lib -lcall_lib_A -lcall_lib_B
// RUN: cat %s | LD_LIBRARY_PATH="%t-dir/lib" %cling 2>&1 | FileCheck %s
// Test: Cling pragma for loading libraries. Lookup and load library Lib_L_AB
// that depends on two libraries Lib_A and Lib_B via file names.
// Lib_L_AB, Lib_A and Lib_B are in LD_LIBRARY_PATH.
// Lookup functions from libraries and use them to print result value.
#pragma cling load("libcall_lib_L_AB")
extern "C" int cling_testlibrary_function();
cling_testlibrary_function()
// CHECK: (int) 357
.q