Skip to content

Commit

Permalink
Linting.
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <michael@openrobotics.org>
  • Loading branch information
mjcarroll committed Mar 26, 2019
1 parent 115ae5d commit 60df764
Show file tree
Hide file tree
Showing 9 changed files with 103 additions and 165 deletions.
23 changes: 0 additions & 23 deletions rclcpp_components/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,29 +38,6 @@ endif()
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

find_package(std_msgs REQUIRED)

set(node_plugins "")

add_library(
test_components
SHARED
test/talker_component.cpp
)
ament_target_dependencies(
test_components
"class_loader"
"rclcpp"
"std_msgs"
)
set(node_plugins "${node_plugins}test_rclcpp_components::Talker;$<TARGET_FILE:test_components>\n")

file(GENERATE
OUTPUT
"${CMAKE_CURRENT_BINARY_DIR}/test_ament_index/$<CONFIG>/share/ament_index/resource_index/rclcpp_components/${PROJECT_NAME}"
CONTENT "${node_plugins}")

endif()

# Install executables
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#ifndef RCLCPP_COMPONENTS__NODE_FACTORY_TEMPLATE_HPP__
#define RCLCPP_COMPONENTS__NODE_FACTORY_TEMPLATE_HPP__

#include <memory>

#include "rclcpp_components/node_factory.hpp"

namespace rclcpp_components
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ class NodeInstanceWrapper
using NodeBaseInterfaceGetter = std::function<
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr(const std::shared_ptr<void> &)>;

NodeInstanceWrapper():
node_instance_(nullptr)
NodeInstanceWrapper()
: node_instance_(nullptr)
{}

NodeInstanceWrapper(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@

#define RCLCPP_COMPONENTS_REGISTER_NODE(NodeClass) \
CLASS_LOADER_REGISTER_CLASS(rclcpp_components::NodeFactoryTemplate<NodeClass>, \
rclcpp_components::NodeFactory)
rclcpp_components::NodeFactory)

#endif // RCLCPP_COMPONENTS__REGISTER_NODE_MACRO_HPP__

33 changes: 14 additions & 19 deletions rclcpp_components/src/component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <memory>
#include <string>
#include <vector>

#include "component_manager.hpp"
#include "filesystem_helper.hpp"
#include "split.hpp"
Expand Down Expand Up @@ -104,20 +108,17 @@ ComponentManager::OnLoadNode(
auto node_factory = loader->createInstance<rclcpp_components::NodeFactory>(clazz);

std::vector<rclcpp::Parameter> parameters;
for (auto & p: request->parameters)
{
for (auto & p : request->parameters) {
parameters.push_back(rclcpp::Parameter::from_parameter_msg(p));
}

std::vector<std::string> remap_rules { request->remap_rules };
std::vector<std::string> remap_rules {request->remap_rules};

if (request->node_name.length())
{
if (request->node_name.length()) {
remap_rules.push_back("__node:=" + request->node_name);
}

if (request->node_namespace.length())
{
if (request->node_namespace.length()) {
remap_rules.push_back("__ns:=" + request->node_namespace);
}

Expand All @@ -130,8 +131,7 @@ ComponentManager::OnLoadNode(
node_wrappers_[node_id] = node_factory->create_node_instance(options);

auto node = node_wrappers_[node_id].get_node_base_interface();
if (auto exec = executor_.lock())
{
if (auto exec = executor_.lock()) {
exec->add_node(node, true);
}
response->full_node_name = node->get_fully_qualified_name();
Expand Down Expand Up @@ -167,18 +167,14 @@ ComponentManager::OnUnloadNode(

auto wrapper = node_wrappers_.find(request->unique_id);

if(wrapper == node_wrappers_.end())
{
if (wrapper == node_wrappers_.end()) {
response->success = false;
std::stringstream ss;
ss << "No node found with unique_id: " << request->unique_id;
response->error_message = ss.str();
RCLCPP_WARN(get_logger(), ss.str());
}
else
{
if (auto exec = executor_.lock())
{
} else {
if (auto exec = executor_.lock()) {
exec->remove_node(wrapper->second.get_node_base_interface());
}
node_wrappers_.erase(wrapper);
Expand All @@ -195,11 +191,10 @@ ComponentManager::OnListNodes(
(void) request_header;
(void) request;

for(auto& wrapper: node_wrappers_)
{
for (auto & wrapper : node_wrappers_) {
response->unique_ids.push_back(wrapper.first);
response->full_node_names.push_back(
wrapper.second.get_node_base_interface()->get_fully_qualified_name());
wrapper.second.get_node_base_interface()->get_fully_qualified_name());
}
}

Expand Down
12 changes: 8 additions & 4 deletions rclcpp_components/src/component_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__
#define RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__
#ifndef COMPONENT_MANAGER_HPP__
#define COMPONENT_MANAGER_HPP__

#include <map>
#include <memory>
#include <string>

#include "ament_index_cpp/get_resource.hpp"
#include "class_loader/class_loader.hpp"
Expand All @@ -38,7 +42,7 @@ class ComponentManager : public rclcpp::Node
using UnloadNode = composition_interfaces::srv::UnloadNode;
using ListNodes = composition_interfaces::srv::ListNodes;

ComponentManager(std::weak_ptr<rclcpp::executor::Executor> executor);
explicit ComponentManager(std::weak_ptr<rclcpp::executor::Executor> executor);

private:
void OnLoadNode(
Expand Down Expand Up @@ -71,4 +75,4 @@ class ComponentManager : public rclcpp::Node

} // namespace rclcpp_components

#endif // RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__
#endif // COMPONENT_MANAGER_HPP__
71 changes: 39 additions & 32 deletions rclcpp_components/src/filesystem_helper.hpp
Original file line number Diff line number Diff line change
@@ -1,47 +1,53 @@
/*
* Copyright (c) 2017, Open Source Robotics Foundation, 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 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 (c) 2017, 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

/// Includes std::filesystem and aliases the namespace to `pluginlib::impl::fs`.
/**
* If std::filesystem is not available the necessary functions are emulated.
*/

#ifndef RCLCPP_COMPONENTS__FILESYSTEM_HELPER_HPP_
#define RCLCPP_COMPONETNS__FILESYSTEM_HELPER_HPP_
#ifndef FILESYSTEM_HELPER_HPP_
#define FILESYSTEM_HELPER_HPP_

#if defined(_MSC_VER)
# if _MSC_VER >= 1900
# include <experimental/filesystem>
namespace rclcpp_components
{
namespace fs = std::experimental::filesystem;
} // namespace components
} // namespace rclcpp_components

# define RCLCPP_COMPONENTS__FILESYSYEM_HELPER__HAS_STD_FILESYSTEM
# endif
Expand All @@ -56,6 +62,7 @@ namespace fs = std::filesystem;
} // namespace rclcpp_components

# define RCLCPP_COMPONENTS__FILESYSYEM_HELPER__HAS_STD_FILESYSTEM
// cppcheck-suppress preprocessorErrorDirective
# elif __has_include(<experimental/filesystem>)
# include <experimental/filesystem>

Expand Down Expand Up @@ -185,4 +192,4 @@ inline bool exists(const path & path_to_check)

#undef RCLCPP_COMPONENTS__FILESYSYEM_HELPER__HAS_STD_FILESYSTEM

#endif // RCLCPP_COMPONENTS__FILESYSTEM_HELPER_HPP_
#endif // FILESYSTEM_HELPER_HPP_
68 changes: 37 additions & 31 deletions rclcpp_components/src/split.hpp
Original file line number Diff line number Diff line change
@@ -1,34 +1,40 @@
/*
* Copyright (c) 2017, Open Source Robotics Foundation, 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 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 (c) 2017, 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 RCLCPP_COMPONENTS__SPLIT_HPP_
#define RCLCPP_COMPONETNS__SPLIT_HPP_
#ifndef SPLIT_HPP_
#define SPLIT_HPP_

#include <regex>
#include <string>
Expand Down Expand Up @@ -68,4 +74,4 @@ std::vector<std::string> split(

} // namespace rclcpp_components

#endif // RCLCPP_COMPONENTS__SPLIT_HPP_
#endif // SPLIT_HPP_
52 changes: 0 additions & 52 deletions rclcpp_components/test/talker_component.cpp

This file was deleted.

0 comments on commit 60df764

Please sign in to comment.