Skip to content

Commit

Permalink
find_library: Centralize functionality here
Browse files Browse the repository at this point in the history
Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
  • Loading branch information
EricCousineau-TRI committed May 2, 2019
1 parent 418f95c commit b575b19
Show file tree
Hide file tree
Showing 8 changed files with 319 additions and 3 deletions.
22 changes: 22 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ cmake_minimum_required(VERSION 3.5)
project(rcpputils)

find_package(ament_cmake REQUIRED)
find_package(ament_cmake_ros REQUIRED)

# Default to C11
if(NOT CMAKE_C_STANDARD)
Expand All @@ -21,6 +22,14 @@ include_directories(include)

ament_export_include_directories(include)

add_library(${PROJECT_NAME}
src/find_library.cpp)
target_include_directories(${PROJECT_NAME}
PUBLIC
include
)
ament_export_libraries(${PROJECT_NAME})

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_lint_auto REQUIRED)
Expand All @@ -36,10 +45,23 @@ if(BUILD_TESTING)
ament_add_gtest(test_split test/test_split.cpp)

ament_add_gtest(test_filesystem_helper test/test_filesystem_helper.cpp)

add_library(toy_test_library SHARED test/toy_test_library.cpp)
ament_add_gtest(test_find_library test/test_find_library.cpp)
target_link_libraries(test_find_library ${PROJECT_NAME} toy_test_library)
set_tests_properties(test_find_library PROPERTIES
ENVIRONMENT
"_TOY_TEST_LIBRARY_DIR=$<TARGET_FILE_DIR:toy_test_library>;_TOY_TEST_LIBRARY=$<TARGET_FILE:toy_test_library>")
endif()

ament_package()

install(
DIRECTORY include/
DESTINATION include)
install(
TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)
15 changes: 12 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,23 @@

`rcpputils` is a C++ API consisting of macros, functions, and data structures intended for use throughout the ROS 2 codebase

This package currently contains:
* Clang thread safety annotation macros
See below sections for what this package currently contains.

## Clang Thread Safety Annotation Macros
the `rcpputils/thread_safety_annotations.hpp` header provides macros for Clang's [Thread Safety Analysis](https://clang.llvm.org/docs/ThreadSafetyAnalysis.html) feature.

The `rcpputils/thread_safety_annotations.hpp` header provides macros for Clang's [Thread Safety Analysis](https://clang.llvm.org/docs/ThreadSafetyAnalysis.html) feature.

The macros allow you to annotate your code, but expand to nothing when using a non-clang compiler, so they are safe for cross-platform use.

To use thread safety annotation in your package (in a Clang+libcxx build), enable the `-Wthread-safety` compiler flag.

For example usage, see [the documentation of this feature](https://clang.llvm.org/docs/ThreadSafetyAnalysis.html) and the tests in `test/test_basic.cpp`

## Library Discovery

In `rcpputils/find_library.hpp`:

* `find_library(library_name)`: Namely used for dynamically loading RMW
implementations.
* For dynamically loading user-defind plugins in C++, please use
[`pluginlib`](https://github.com/ros/pluginlib) instead.
42 changes: 42 additions & 0 deletions include/rcpputils/find_library.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCPPUTILS__FIND_LIBRARY_HPP_
#define RCPPUTILS__FIND_LIBRARY_HPP_

#include <string>

#include "rcpputils/visibility_control.hpp"

namespace rcpputils
{

/// Finds a library located in the OS's specified environment variable for
/// library paths and returns the absolute filesystem path, including the
/// appropriate prefix and extension.
/**
* The environment variable and file format per platform:
* * Linux: `${LD_LIBRARY_PATH}`, `lib{}.so`
* * Apple: `${DYLD_LIBRARY_PATH}`, `lib{}.dyld`
* * Windows: `%PATH%`, `{}.dll`
*
* \param[in] library_name Name of the library to find.
* \return Absolute path of library.
*/
RCPPUTILS_PUBLIC
std::string find_library_path(const std::string & library_name);

} // namespace rcpputils

#endif // RCPPUTILS__FIND_LIBRARY_HPP_
64 changes: 64 additions & 0 deletions include/rcpputils/visibility_control.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
// Copyright (c) 2019, Open Source Robotics Foundation, Inc.
// All rights reserved.
//
// Software License Agreement (BSD License 2.0)
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Willow Garage, Inc. nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#ifndef RCPPUTILS__VISIBILITY_CONTROL_HPP_
#define RCPPUTILS__VISIBILITY_CONTROL_HPP_

// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
// https://gcc.gnu.org/wiki/Visibility

#if defined _WIN32 || defined __CYGWIN__
#ifdef __GNUC__
#define RCPPUTILS_EXPORT __attribute__ ((dllexport))
#define RCPPUTILS_IMPORT __attribute__ ((dllimport))
#else
#define RCPPUTILS_EXPORT __declspec(dllexport)
#define RCPPUTILS_IMPORT __declspec(dllimport)
#endif
#ifdef RCPPUTILS_BUILDING_LIBRARY
#define RCPPUTILS_PUBLIC RCPPUTILS_EXPORT
#else
#define RCPPUTILS_PUBLIC RCPPUTILS_IMPORT
#endif
#define RCPPUTILS_PUBLIC_TYPE RCPPUTILS_PUBLIC
#define RCPPUTILS_LOCAL
#else
#define RCPPUTILS_EXPORT __attribute__ ((visibility("default")))
#define RCPPUTILS_IMPORT
#if __GNUC__ >= 4
#define RCPPUTILS_PUBLIC __attribute__ ((visibility("default")))
#define RCPPUTILS_LOCAL __attribute__ ((visibility("hidden")))
#else
#define RCPPUTILS_PUBLIC
#define RCPPUTILS_LOCAL
#endif
#define RCPPUTILS_PUBLIC_TYPE
#endif

#endif // RCPPUTILS__VISIBILITY_CONTROL_HPP_
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_ros</buildtool_depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
94 changes: 94 additions & 0 deletions src/find_library.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "rcpputils/find_library.hpp"

#include <cassert>
#include <cstddef>

#include <list>
#include <fstream>
#include <sstream>
#include <string>

namespace rcpputils
{

namespace
{

#ifdef _WIN32
static constexpr char kPathVar[] = "PATH";
static constexpr char kPathSeparator = ';';
static constexpr char kSolibPrefix[] = "";
static constexpr char kSolibExtension[] = ".dll";
#elif __APPLE__
static constexpr char kPathVar[] = "DYLD_LIBRARY_PATH";
static constexpr char kPathSeparator = ':';
static constexpr char kSolibPrefix[] = "lib";
static constexpr char kSolibExtension[] = ".dylib";
#else
static constexpr char kPathVar[] = "LD_LIBRARY_PATH";
static constexpr char kPathSeparator = ':';
static constexpr char kSolibPrefix[] = "lib";
static constexpr char kSolibExtension[] = ".so";
#endif

std::string get_env_var(const char * kPathVar)
{
char * value = getenv(kPathVar);
return value ? value : "";
}

std::list<std::string> split(const std::string & value, const char delimiter)
{
std::list<std::string> list;
std::istringstream ss(value);
std::string s;
while (std::getline(ss, s, delimiter)) {
list.push_back(s);
}
return list;
}

bool is_file_exist(const char * filename)
{
std::ifstream h(filename);
return h.good();
}

} // namespace

std::string find_library_path(const std::string & library_name)
{
// TODO(eric.cousineau): Does Poco provide this functionality
// (ros2/rcpputils#7)?
// TODO(eric.cousineau): Have this return a library pointer instead
// (ros2/rcpputils#8).
std::string search_path = get_env_var(kPathVar);
std::list<std::string> search_paths = split(search_path, kPathSeparator);

std::string filename = kSolibPrefix;
filename += library_name + kSolibExtension;

for (const auto & search_path : search_paths) {
std::string path = search_path + "/" + filename;
if (is_file_exist(path.c_str())) {
return path;
}
}
return "";
}

} // namespace rcpputils
58 changes: 58 additions & 0 deletions test/test_find_library.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <string>

#include "gtest/gtest.h"

#include "rcpputils/find_library.hpp"

namespace rcpputils
{
namespace
{

TEST(test_find_library, find_library)
{
// Get ground-truth values from CTest properties.
const char * toy_lib_expected = getenv("_TOY_TEST_LIBRARY");
EXPECT_NE(toy_lib_expected, nullptr);
const char * toy_lib_dir = getenv("_TOY_TEST_LIBRARY_DIR");
EXPECT_NE(toy_lib_dir, nullptr);

// Set our relevant path variable.
const char * env_var{};
#ifdef _WIN32
env_var = "PATH";
#elif __APPLE__
env_var = "DYLD_LIBRARY_PATH";
#else
env_var = "LD_LIBRARY_PATH";
#endif
const int override = 1;
setenv(env_var, toy_lib_dir, override);

// Positive test.
const std::string toy_lib_actual = find_library_path("toy_test_library");
EXPECT_EQ(toy_lib_actual, toy_lib_expected);

// (Hopefully) Negative test.
const std::string bad_path = find_library_path(
"this_is_a_junk_libray_name_please_dont_define_this_if_you_do_then_"
"you_are_really_naughty");
EXPECT_EQ(bad_path, "");
}

} // namespace
} // namespace rcpputils
26 changes: 26 additions & 0 deletions test/toy_test_library.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

/// @file
/// Trivial library to ensure we have some linking present.

namespace toy_test_library
{

int add_one(int x)
{
return x + 1;
}

} // namespace toy_test_library

0 comments on commit b575b19

Please sign in to comment.