Skip to content

Commit

Permalink
Add an outline for the "passthrough controller"
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe committed Mar 30, 2023
1 parent 82a4e24 commit 97bca55
Show file tree
Hide file tree
Showing 7 changed files with 303 additions and 0 deletions.
73 changes: 73 additions & 0 deletions passthrough_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
cmake_minimum_required(VERSION 3.16)
project(passthrough_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
control_msgs
controller_interface
hardware_interface
parameter_traits
pluginlib
rclcpp
rclcpp_lifecycle
realtime_tools
)

find_package(ament_cmake REQUIRED)
find_package(backward_ros REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()

add_library(passthrough_controller SHARED
src/passthrough_controller.cpp
)
target_compile_features(passthrough_controller PUBLIC cxx_std_17)
target_include_directories(passthrough_controller PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/passthrough_controller>
)
# target_link_libraries(passthrough_controller PUBLIC
# passthrough_controller_parameters
# )
ament_target_dependencies(passthrough_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})

# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(passthrough_controller PRIVATE "passthrough_controller_BUILDING_DLL")

pluginlib_export_plugin_description_file(controller_interface passthrough_controller.xml)

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(controller_manager REQUIRED)
find_package(ros2_control_test_assets REQUIRED)

ament_add_gmock(test_load_controller test/test_load_controller.cpp)
target_include_directories(test_load_controller PRIVATE include)
ament_target_dependencies(
test_load_controller
controller_manager
ros2_control_test_assets
)
endif()

install(
DIRECTORY include/
DESTINATION include/passthrough_controller
)

install(TARGETS
passthrough_controller
EXPORT export_passthrough_controller
RUNTIME DESTINATION bin
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
)

ament_export_targets(export_passthrough_controller HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
// Copyright (c) 2023, PAL Robotics
//
// 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 PASSTHROUGH_CONTROLLER__PASSTHROUGH_CONTROLLER_HPP_
#define PASSTHROUGH_CONTROLLER__PASSTHROUGH_CONTROLLER_HPP_

#include <controller_interface/chainable_controller_interface.hpp>

#include "passthrough_controller/visibility_control.h"

namespace passthrough_controller
{
class PassthroughController : public controller_interface::ChainableControllerInterface
{
public:
PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC
PassthroughController(){}

PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::CallbackReturn on_init() override
{
return controller_interface::CallbackReturn::SUCCESS;
}

PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::InterfaceConfiguration command_interface_configuration() const override
{
controller_interface::InterfaceConfiguration command_interfaces_config;
return command_interfaces_config;
}

PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::InterfaceConfiguration state_interface_configuration() const override
{
controller_interface::InterfaceConfiguration state_interfaces_config;
return state_interfaces_config;
}

PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */) override
{
return controller_interface::return_type::OK;
}

protected:
std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override
{
return std::vector<hardware_interface::CommandInterface>();
}

PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC
bool on_set_chained_mode(bool /* chained_mode */) override
{
return true;
}

PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::return_type update_and_write_commands(
const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */) override
{
return controller_interface::return_type::OK;
}
};

} // namespace passthrough_controller

#endif // PASSTHROUGH_CONTROLLER__PASSTHROUGH_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
// Copyright (c) 2023, PAL Robotics
//
// 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 PASSTHROUGH_CONTROLLER__VISIBILITY_CONTROL_H_
#define PASSTHROUGH_CONTROLLER__VISIBILITY_CONTROL_H_

// 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 PASSTHROUGH_CONTROLLER__VISIBILITY_EXPORT __attribute__((dllexport))
#define PASSTHROUGH_CONTROLLER__VISIBILITY_IMPORT __attribute__((dllimport))
#else
#define PASSTHROUGH_CONTROLLER__VISIBILITY_EXPORT __declspec(dllexport)
#define PASSTHROUGH_CONTROLLER__VISIBILITY_IMPORT __declspec(dllimport)
#endif
#ifdef PASSTHROUGH_CONTROLLER__VISIBILITY_BUILDING_DLL
#define PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC PASSTHROUGH_CONTROLLER__VISIBILITY_EXPORT
#else
#define PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC PASSTHROUGH_CONTROLLER__VISIBILITY_IMPORT
#endif
#define PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC_TYPE PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC
#define PASSTHROUGH_CONTROLLER__VISIBILITY_LOCAL
#else
#define PASSTHROUGH_CONTROLLER__VISIBILITY_EXPORT __attribute__((visibility("default")))
#define PASSTHROUGH_CONTROLLER__VISIBILITY_IMPORT
#if __GNUC__ >= 4
#define PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC __attribute__((visibility("default")))
#define PASSTHROUGH_CONTROLLER__VISIBILITY_LOCAL __attribute__((visibility("hidden")))
#else
#define PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC
#define PASSTHROUGH_CONTROLLER__VISIBILITY_LOCAL
#endif
#define PASSTHROUGH_CONTROLLER__VISIBILITY_PUBLIC_TYPE
#endif

#endif // PASSTHROUGH_CONTROLLER__VISIBILITY_CONTROL_H_
29 changes: 29 additions & 0 deletions passthrough_controller/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>passthrough_controller</name>
<version>0.0.0</version>
<description>A simple demo of chainable controllers. It passes commands through without change.</description>
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>
<maintainer email="[email protected]">Andy Zelenak</maintainer>
<license>Apache-2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>control_msgs</depend>
<depend>controller_interface</depend>
<depend>hardware_interface</depend>
<depend>parameter_traits</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>realtime_tools</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>controller_manager</test_depend>
<test_depend>ros2_control_test_assets</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
9 changes: 9 additions & 0 deletions passthrough_controller/passthrough_controller.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<library path="passthrough_controller">
<class name="passthrough_controller/PassthroughController"
type="passthrough_controller::PassthroughController"
base_class_type="controller_interface::ChainableControllerInterface">
<description>
A simple demo of chainable controllers. It passes commands through without change.
</description>
</class>
</library>
25 changes: 25 additions & 0 deletions passthrough_controller/src/passthrough_controller.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// Copyright (c) 2023, PAL Robotics
//
// 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 "passthrough_controller/passthrough_controller.hpp"

namespace passthrough_controller
{

} // namespace passthrough_controller

#include "pluginlib/class_list_macros.hpp"

PLUGINLIB_EXPORT_CLASS(
passthrough_controller::PassthroughController, controller_interface::ChainableControllerInterface)
40 changes: 40 additions & 0 deletions passthrough_controller/test/test_load_controller.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
// Copyright (c) 2023, PAL Robotics
//
// 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 <gmock/gmock.h>
#include <memory>

#include "controller_manager/controller_manager.hpp"
#include "hardware_interface/resource_manager.hpp"
#include "rclcpp/executor.hpp"
#include "rclcpp/executors/single_threaded_executor.hpp"
#include "rclcpp/utilities.hpp"
#include "ros2_control_test_assets/descriptions.hpp"

TEST(TestLoadPidController, load_controller)
{
rclcpp::init(0, nullptr);

std::shared_ptr<rclcpp::Executor> executor =
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

controller_manager::ControllerManager cm(
std::make_unique<hardware_interface::ResourceManager>(
ros2_control_test_assets::minimal_robot_urdf),
executor, "test_controller_manager");

ASSERT_NO_THROW(cm.load_controller("test_passthrough_controller", "passthrough_controller/PassthroughController"));

rclcpp::shutdown();
}

0 comments on commit 97bca55

Please sign in to comment.