Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/master' into issue/3
Browse files Browse the repository at this point in the history
# Conflicts:
#	CMakeLists.txt
  • Loading branch information
EricCousineau-TRI committed May 2, 2019
2 parents dd6c0ad + 418f95c commit 5e75d84
Show file tree
Hide file tree
Showing 7 changed files with 574 additions and 1 deletion.
4 changes: 4 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,10 @@ if(BUILD_TESTING)

ament_add_gtest(test_basic test/test_basic.cpp)

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)
Expand Down
1 change: 1 addition & 0 deletions CODEOWNERS
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
* @ros2/aws-robotics-code-owners
165 changes: 165 additions & 0 deletions include/rcpputils/filesystem_helper.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
// 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.
//
// This file is originally from:
// https://github.com/ros/pluginlib/blob/1a4de29fa55173e9b897ca8ff57ebc88c047e0b3/pluginlib/include/pluginlib/impl/filesystem_helper.hpp

/**
* If std::filesystem is not available the necessary functions are emulated.
*
* Note: Once std::filesystem is supported on all ROS2 platforms, this class
* can be deprecated in favor of the built-in functionality.
*/

#ifndef RCPPUTILS__FILESYSTEM_HELPER_HPP_
#define RCPPUTILS__FILESYSTEM_HELPER_HPP_

#include <algorithm>
#include <string>
#include <vector>

#ifdef _WIN32
# define RCPPUTILS_IMPL_OS_DIRSEP '\\'
#else
# define RCPPUTILS_IMPL_OS_DIRSEP '/'
#endif

#ifdef _WIN32
# include <io.h>
# define access _access_s
#else
# include <unistd.h>
#endif

#include "rcpputils/split.hpp"

namespace rcpputils
{
namespace fs
{

static constexpr const char kPreferredSeparator = RCPPUTILS_IMPL_OS_DIRSEP;

class path
{
public:
path()
: path("")
{}

path(const std::string & p) // NOLINT(runtime/explicit): this is a conversion constructor
: path_(p), path_as_vector_(split(p, kPreferredSeparator))
{
std::replace(path_.begin(), path_.end(), '\\', kPreferredSeparator);
std::replace(path_.begin(), path_.end(), '/', kPreferredSeparator);
}

std::string string() const
{
return path_;
}

bool exists() const
{
return access(path_.c_str(), 0) == 0;
}

bool is_absolute() const
{
return path_.compare(0, 1, "/") == 0 || path_.compare(1, 2, ":\\") == 0;
}

std::vector<std::string>::const_iterator cbegin() const
{
return path_as_vector_.cbegin();
}

std::vector<std::string>::const_iterator cend() const
{
return path_as_vector_.cend();
}

path parent_path() const
{
path parent("");
for (auto it = this->cbegin(); it != --this->cend(); ++it) {
parent /= *it;
}
return parent;
}

path filename() const
{
return path_.empty() ? path() : *--this->cend();
}

path operator/(const std::string & other)
{
return this->operator/(path(other));
}

path & operator/=(const std::string & other)
{
this->operator/=(path(other));
return *this;
}

path operator/(const path & other)
{
return path(*this).operator/=(other);
}

path & operator/=(const path & other)
{
this->path_ += kPreferredSeparator + other.string();
this->path_as_vector_.insert(
std::end(this->path_as_vector_),
std::begin(other.path_as_vector_), std::end(other.path_as_vector_));
return *this;
}

private:
std::string path_;
std::vector<std::string> path_as_vector_;
};

inline bool exists(const path & path_to_check)
{
return path_to_check.exists();
}

#undef RCPPUTILS_IMPL_OS_DIRSEP

} // namespace fs
} // namespace rcpputils

#endif // RCPPUTILS__FILESYSTEM_HELPER_HPP_
71 changes: 71 additions & 0 deletions include/rcpputils/split.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
// 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.
//
// This file is originally from:
// https://github.com/ros/pluginlib/blob/1a4de29fa55173e9b897ca8ff57ebc88c047e0b3/pluginlib/include/pluginlib/impl/split.hpp

#ifndef RCPPUTILS__SPLIT_HPP_
#define RCPPUTILS__SPLIT_HPP_

#include <sstream>
#include <string>
#include <vector>

namespace rcpputils
{

/// Split a specified input into tokens using a delimiter.
/**
* The returned vector will contain the tokens split from the input
*
* \param[in] input the input string to be split
* \param[in] delim the dlelimiter used to split the input string
* \return A vector of tokens.
*/
inline std::vector<std::string>
split(const std::string & input, char delim, bool skip_empty = false)
{
std::vector<std::string> result;
std::stringstream ss;
ss.str(input);
std::string item;
while (std::getline(ss, item, delim)) {
if (skip_empty && item == "") {
continue;
}
result.push_back(item);
}
return result;
}
} // namespace rcpputils

#endif // RCPPUTILS__SPLIT_HPP_
6 changes: 5 additions & 1 deletion test/test_basic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,6 +136,11 @@ struct FakeGuarded
* pData = 0;
}

~FakeGuarded()
{
delete pData;
}

int incr_HaveGuard() RCPPUTILS_TSA_REQUIRES(mu)
{
return data++;
Expand Down Expand Up @@ -244,7 +249,6 @@ TEST(test_tsa, ptr_guard) {
int * old = guarded.pData;
guarded.pData = new int; // pData itself is not protected by the mutex
delete old;
delete guarded.pData;
}

TEST(test_tsa, shared_capability) {
Expand Down
105 changes: 105 additions & 0 deletions test/test_filesystem_helper.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,105 @@
// 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 <gtest/gtest.h>

#include <string>

#include "rcpputils/filesystem_helper.hpp"

#ifdef WIN32
static constexpr const bool is_win32 = true;
#else
static constexpr const bool is_win32 = false;
#endif

using path = rcpputils::fs::path;

TEST(TestFilesystemHelper, join_path)
{
auto p = path("foo") / path("bar");

if (is_win32) {
EXPECT_EQ("foo\\bar", p.string());
} else {
EXPECT_EQ("foo/bar", p.string());
}
}

TEST(TestFilesystemHelper, to_native_path)
{
{
auto p = path("/foo/bar/baz");
if (is_win32) {
EXPECT_EQ("\\foo\\bar\\baz", p.string());
} else {
EXPECT_EQ("/foo/bar/baz", p.string());
}
}
{
auto p = path("\\foo\\bar\\baz");
if (is_win32) {
EXPECT_EQ("\\foo\\bar\\baz", p.string());
} else {
EXPECT_EQ("/foo/bar/baz", p.string());
}
}
{
auto p = path("/foo//bar/baz");
if (is_win32) {
EXPECT_EQ("\\foo\\\\bar\\baz", p.string());
} else {
EXPECT_EQ("/foo//bar/baz", p.string());
}
}
{
auto p = path("\\foo\\\\bar\\baz");
if (is_win32) {
EXPECT_EQ("\\foo\\\\bar\\baz", p.string());
} else {
EXPECT_EQ("/foo//bar/baz", p.string());
}
}
}

TEST(TestFilesystemHelper, is_absolute)
{
if (is_win32) {
{
auto p = path("C:\\foo\\bar\\baz");
EXPECT_TRUE(p.is_absolute());
}
{
auto p = path("D:\\foo\\bar\\baz");
EXPECT_TRUE(p.is_absolute());
}
{
auto p = path("C:/foo/bar/baz");
EXPECT_TRUE(p.is_absolute());
}
{
auto p = path("foo/bar/baz");
EXPECT_FALSE(p.is_absolute());
}
} else {
{
auto p = path("/foo/bar/baz");
EXPECT_TRUE(p.is_absolute());
}
{
auto p = path("foo/bar/baz");
EXPECT_FALSE(p.is_absolute());
}
}
}
Loading

0 comments on commit 5e75d84

Please sign in to comment.