diff --git a/CMakeLists.txt b/CMakeLists.txt index cf1343b..a42a0ac 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,6 +3,8 @@ cmake_minimum_required(VERSION 3.5) project(rcpputils) find_package(ament_cmake REQUIRED) +find_package(ament_cmake_ros REQUIRED) +find_package(rcutils REQUIRED) # Default to C11 if(NOT CMAKE_C_STANDARD) @@ -21,6 +23,19 @@ include_directories(include) ament_export_include_directories(include) +add_library(${PROJECT_NAME} + src/find_library.cpp) +target_include_directories(${PROJECT_NAME} + PUBLIC + include +) +if(WIN32) + target_compile_definitions(${PROJECT_NAME} + PRIVATE "RCPPUTILS_BUILDING_LIBRARY") +endif() +ament_target_dependencies(${PROJECT_NAME} rcutils) +ament_export_libraries(${PROJECT_NAME}) + if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) find_package(ament_lint_auto REQUIRED) @@ -36,6 +51,13 @@ 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(test_library SHARED test/test_library.cpp) + ament_add_gtest(test_find_library test/test_find_library.cpp) + target_link_libraries(test_find_library ${PROJECT_NAME} test_library) + set_tests_properties(test_find_library PROPERTIES + ENVIRONMENT + "_TEST_LIBRARY_DIR=$;_TEST_LIBRARY=$") endif() ament_package() @@ -43,3 +65,9 @@ ament_package() install( DIRECTORY include/ DESTINATION include) +install( + TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) diff --git a/README.md b/README.md index 18cd41d..28cb5a9 100644 --- a/README.md +++ b/README.md @@ -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. diff --git a/include/rcpputils/find_library.hpp b/include/rcpputils/find_library.hpp new file mode 100644 index 0000000..292b984 --- /dev/null +++ b/include/rcpputils/find_library.hpp @@ -0,0 +1,44 @@ +// 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 + +#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. + * \throws std::runtime_error if an error is encountered when accessing + * environment variables. + */ +RCPPUTILS_PUBLIC +std::string find_library_path(const std::string & library_name); + +} // namespace rcpputils + +#endif // RCPPUTILS__FIND_LIBRARY_HPP_ diff --git a/include/rcpputils/visibility_control.hpp b/include/rcpputils/visibility_control.hpp new file mode 100644 index 0000000..b03720e --- /dev/null +++ b/include/rcpputils/visibility_control.hpp @@ -0,0 +1,67 @@ +// 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 copyright holders 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_ diff --git a/package.xml b/package.xml index 18a080b..c50d0f8 100644 --- a/package.xml +++ b/package.xml @@ -8,6 +8,9 @@ Apache License 2.0 ament_cmake + ament_cmake_ros + + rcutils ament_lint_common ament_lint_auto diff --git a/src/find_library.cpp b/src/find_library.cpp new file mode 100644 index 0000000..ae8f3ef --- /dev/null +++ b/src/find_library.cpp @@ -0,0 +1,91 @@ +// 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 +#include + +#include +#include +#include +#include + +#include "rcutils/filesystem.h" +#include "rcutils/get_env.h" + +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) +{ + const char * value{}; + const char * err = rcutils_get_env(kPathVar, &value); + if (err) { + throw std::runtime_error(err); + } + return value ? value : ""; +} + +std::list split(const std::string & value, const char delimiter) +{ + std::list list; + std::istringstream ss(value); + std::string s; + while (std::getline(ss, s, delimiter)) { + list.push_back(s); + } + return list; +} + +} // namespace + +std::string find_library_path(const std::string & library_name) +{ + std::string search_path = get_env_var(kPathVar); + std::list 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 (rcutils_is_file(path.c_str())) { + return path; + } + } + return ""; +} + +} // namespace rcpputils diff --git a/test/test_find_library.cpp b/test/test_find_library.cpp new file mode 100644 index 0000000..9a007ed --- /dev/null +++ b/test/test_find_library.cpp @@ -0,0 +1,68 @@ +// 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 + +#include + +#include "gtest/gtest.h" + +#include "rcutils/get_env.h" +#include "rcpputils/find_library.hpp" + +namespace rcpputils +{ +namespace +{ + +TEST(test_find_library, find_library) +{ + // Get ground-truth values from CTest properties. + const char * test_lib_expected{}; + EXPECT_EQ(rcutils_get_env("_TEST_LIBRARY", &test_lib_expected), nullptr); + EXPECT_NE(test_lib_expected, nullptr); + const char * test_lib_dir{}; + EXPECT_EQ(rcutils_get_env("_TEST_LIBRARY_DIR", &test_lib_dir), nullptr); + EXPECT_NE(test_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 + +#ifdef _WIN32 + EXPECT_EQ(_putenv_s(env_var, test_lib_dir), 0); +#else + const int override = 1; + EXPECT_EQ(setenv(env_var, test_lib_dir, override), 0); +#endif + + // Positive test. + const std::string test_lib_actual = find_library_path("test_library"); + EXPECT_EQ(test_lib_actual, test_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 diff --git a/test/test_library.cpp b/test/test_library.cpp new file mode 100644 index 0000000..66f4596 --- /dev/null +++ b/test/test_library.cpp @@ -0,0 +1,30 @@ +// 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 for +/// `test_find_library`. + +#include "rcpputils/visibility_control.hpp" + +namespace test_library +{ + +RCPPUTILS_EXPORT +int add_one(int x) +{ + return x + 1; +} + +} // namespace test_library