Skip to content

Commit

Permalink
Towards Quality Level 1 - Added common_linters and fixed tests (#43)
Browse files Browse the repository at this point in the history
* Added common_linters and fixed tests

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Removed test/CMakeLists.txt

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Update resource_retriever/test/test.cpp

Co-Authored-By: Chris Lalancette <clalancette@openrobotics.org>

* Const exceptions

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Added message when throws an exception

Signed-off-by: ahcorde <ahcorde@gmail.com>

* combine file plut error

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Removed trace when the test is right

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Installing only the test.txt file when BUILD_TESTING is active

Signed-off-by: ahcorde <ahcorde@gmail.com>

* no need to check for target in test

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Attemp to fix windows path

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Fixed warning on Windows

Signed-off-by: ahcorde <ahcorde@gmail.com>

Co-authored-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
ahcorde and clalancette committed Apr 22, 2020
1 parent a997a38 commit 9f02908
Show file tree
Hide file tree
Showing 9 changed files with 264 additions and 256 deletions.
45 changes: 41 additions & 4 deletions resource_retriever/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ find_package(ament_index_cpp REQUIRED)
# TODO(wjwwood): remove libcurl_vendor and just use system curl when possible
find_package(libcurl_vendor REQUIRED)

# TODO(wjwwood): split cpp and python apis into separate packages and fix python api
# TODO(wjwwood): split cpp and python apis into separate packages

add_library(${PROJECT_NAME} src/retriever.cpp)
target_include_directories(${PROJECT_NAME}
Expand All @@ -38,11 +38,48 @@ ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET)
ament_export_dependencies(ament_index_cpp)
ament_export_dependencies(libcurl_vendor)

ament_python_install_package(${PROJECT_NAME}
PACKAGE_DIR src/${PROJECT_NAME})

if(BUILD_TESTING)
# TODO(wjwwood): add ament linters
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_lint_auto REQUIRED)

list(APPEND AMENT_LINT_AUTO_EXCLUDE
ament_cmake_cppcheck
ament_cmake_uncrustify
)
ament_lint_auto_find_test_dependencies()

ament_cppcheck(LANGUAGE "c++")
ament_uncrustify(LANGUAGE "C++")

ament_add_gtest(${PROJECT_NAME}_test test/test.cpp)
target_link_libraries(${PROJECT_NAME}_test ${PROJECT_NAME})

# Python test
# Provides PYTHON_EXECUTABLE_DEBUG
find_package(python_cmake_module REQUIRED)
find_package(PythonExtra REQUIRED)

set(_PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE}")
if(WIN32 AND CMAKE_BUILD_TYPE STREQUAL "Debug")
set(PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE_DEBUG}")
endif()

find_package(ament_cmake_pytest REQUIRED)
ament_add_pytest_test(resource_retriever_python_test test/test.py
PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE}"
APPEND_ENV PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR}
TIMEOUT 60
)

set(PYTHON_EXECUTABLE "${_PYTHON_EXECUTABLE}")

# TODO(wjwwood): reenable tests from ROS 1
# add_subdirectory(test EXCLUDE_FROM_ALL)
install(
FILES test/test.txt
DESTINATION share/${PROJECT_NAME}/test
)
endif()

install(
Expand Down
74 changes: 38 additions & 36 deletions resource_retriever/include/resource_retriever/retriever.h
Original file line number Diff line number Diff line change
@@ -1,32 +1,33 @@
/*
* Copyright (C) 2009, Willow Garage, Inc.
*
* 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 names of Stanford University or 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.
*/
// Copyright 2009, Willow Garage, Inc. All rights reserved.
//
// 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 HOLDER 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 RESOURCE_RETRIEVER_RETRIEVER_H
#define RESOURCE_RETRIEVER_RETRIEVER_H
#ifndef RESOURCE_RETRIEVER__RETRIEVER_H_
#define RESOURCE_RETRIEVER__RETRIEVER_H_

#include <cstdint>
#include <memory>
Expand All @@ -39,13 +40,13 @@ typedef void CURL;

namespace resource_retriever
{

class Exception : public std::runtime_error
{
public:
Exception(const std::string& file, const std::string& error_msg)
Exception(const std::string & file, const std::string & error_msg)
: std::runtime_error("Error retrieving file [" + file + "]: " + error_msg)
{}
{
}
};

/**
Expand All @@ -55,7 +56,8 @@ struct MemoryResource
{
MemoryResource()
: size(0)
{}
{
}

std::shared_ptr<uint8_t> data;
size_t size;
Expand All @@ -78,14 +80,14 @@ class RESOURCE_RETRIEVER_PUBLIC Retriever
* \return The file, loaded into memory
* \throws resource_retriever::Exception if anything goes wrong.
*/
MemoryResource get(const std::string& url);
MemoryResource get(const std::string & url);

private:
Retriever(const Retriever & ret) = delete;

CURL* curl_handle_;
CURL * curl_handle_;
};

} // namespace resource_retriever
} // namespace resource_retriever

#endif // RESOURCE_RETRIEVER_RETRIEVER_H
#endif // RESOURCE_RETRIEVER__RETRIEVER_H_
7 changes: 7 additions & 0 deletions resource_retriever/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,15 @@
<buildtool_depend>ament_cmake_ros</buildtool_depend>

<depend>ament_index_cpp</depend>
<depend>ament_index_python</depend>
<depend>libcurl_vendor</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>python_cmake_module</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
1 change: 1 addition & 0 deletions resource_retriever/setup.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
from distutils.core import setup

from catkin_pkg.python_setup import generate_distutils_setup

d = generate_distutils_setup()
Expand Down
78 changes: 40 additions & 38 deletions resource_retriever/src/resource_retriever/__init__.py
Original file line number Diff line number Diff line change
@@ -1,39 +1,35 @@
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
# Copyright 2008, Willow Garage, Inc. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
# 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 nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# 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.
# * 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_holder} 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 HOLDER 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.

import sys

from ament_index_python import get_package_share_directory

import roslib; roslib.load_manifest('resource_retriever')
import subprocess
import rospkg
try:
from urllib.request import urlopen
from urllib.error import URLError
Expand All @@ -42,30 +38,36 @@
from urllib2 import URLError

PACKAGE_PREFIX = 'package://'
r = rospkg.RosPack()

def get_filename(url, use_protocol=True ):

def get_filename(url, use_protocol=True):
mod_url = url
if url.find(PACKAGE_PREFIX) == 0:
mod_url = url[len(PACKAGE_PREFIX):]
pos = mod_url.find('/')
if pos == -1:
raise Exception("Could not parse package:// format into file:// format for "+url)
raise Exception('Could not parse package:// format into file:// format for ' + url)

package = mod_url[0:pos]
mod_url = mod_url[pos:]
package_path = r.get_path(package)
package_path = get_package_share_directory(package)

if use_protocol:
protocol = "file://"
protocol = 'file://'
else:
protocol = ""
mod_url = protocol + package_path + mod_url;
protocol = ''
if sys.platform.startswith('win'):
path_without_protocol = package_path + mod_url
path_without_protocol = '/' + path_without_protocol.replace('/', '\\')
mod_url = protocol + path_without_protocol
else:
mod_url = protocol + package_path + mod_url
return mod_url


def get(url):
filename = get_filename(url)
try:
return urlopen(filename).read()
except URLError:
raise Exception("Invalid URL: {}".format(filename))
raise Exception('Invalid URL: {}'.format(filename))
Loading

0 comments on commit 9f02908

Please sign in to comment.