Skip to content

Commit 7c7a8c9

Browse files
committed
Merge branch 'refactoring_to_moprim_base_controller' into moprim_from_traj_controller_with_base_controller
2 parents 688c31b + a348921 commit 7c7a8c9

18 files changed

+1043
-1
lines changed
Lines changed: 102 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,102 @@
1+
cmake_minimum_required(VERSION 3.10)
2+
project(chained_filter_controller)
3+
4+
find_package(ros2_control_cmake REQUIRED)
5+
set_compiler_options()
6+
export_windows_symbols()
7+
8+
# Dependencies
9+
set(THIS_PACKAGE_INCLUDE_DEPENDS
10+
controller_interface
11+
generate_parameter_library
12+
filters
13+
hardware_interface
14+
pluginlib
15+
rclcpp
16+
rclcpp_lifecycle
17+
)
18+
find_package(ament_cmake REQUIRED)
19+
find_package(backward_ros REQUIRED)
20+
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
21+
find_package(${Dependency} REQUIRED)
22+
endforeach()
23+
24+
# Generate parameters from YAML
25+
generate_parameter_library(
26+
chained_filter_parameters
27+
src/chained_filter_parameters.yaml
28+
)
29+
30+
# Library definition
31+
add_library(${PROJECT_NAME} SHARED
32+
src/chained_filter.cpp
33+
)
34+
target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_17)
35+
target_include_directories(${PROJECT_NAME} PUBLIC
36+
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
37+
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>
38+
)
39+
40+
# Dependencies
41+
target_link_libraries(${PROJECT_NAME}
42+
PUBLIC
43+
chained_filter_parameters
44+
controller_interface::controller_interface
45+
hardware_interface::hardware_interface
46+
filters::filter_chain
47+
pluginlib::pluginlib
48+
rclcpp::rclcpp
49+
rclcpp_lifecycle::rclcpp_lifecycle
50+
)
51+
52+
# Export the plugin description
53+
pluginlib_export_plugin_description_file(controller_interface plugin_description.xml)
54+
55+
if(BUILD_TESTING)
56+
find_package(ament_cmake_gmock REQUIRED)
57+
find_package(controller_manager REQUIRED)
58+
find_package(ros2_control_test_assets REQUIRED)
59+
60+
add_rostest_with_parameters_gmock(test_chained_filter_controller
61+
test/test_chained_filter.cpp
62+
${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_chained_filter.yaml
63+
)
64+
target_link_libraries(test_chained_filter_controller
65+
${PROJECT_NAME}
66+
)
67+
68+
add_rostest_with_parameters_gmock(test_multiple_chained_filter_controller
69+
test/test_multiple_chained_filter.cpp
70+
${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_multiple_chained_filter.yaml
71+
)
72+
target_link_libraries(test_multiple_chained_filter_controller
73+
${PROJECT_NAME}
74+
)
75+
76+
add_definitions(-DTEST_FILES_DIRECTORY="${CMAKE_CURRENT_SOURCE_DIR}/test")
77+
ament_add_gmock(test_load_chained_filter_controller test/test_load_chained_filter_controller.cpp)
78+
target_link_libraries(test_load_chained_filter_controller
79+
controller_manager::controller_manager
80+
ros2_control_test_assets::ros2_control_test_assets
81+
)
82+
83+
endif()
84+
85+
install(
86+
DIRECTORY include/
87+
DESTINATION include/${PROJECT_NAME}
88+
)
89+
90+
install(
91+
TARGETS ${PROJECT_NAME}
92+
chained_filter_parameters
93+
EXPORT export_${PROJECT_NAME}
94+
ARCHIVE DESTINATION lib
95+
LIBRARY DESTINATION lib
96+
RUNTIME DESTINATION bin
97+
)
98+
99+
# Export targets and dependencies
100+
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
101+
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
102+
ament_package()
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/chained_filter_controller/doc/userdoc.rst
2+
3+
.. _chained_filter_controller_userdoc:
4+
5+
Chained Filter Controller
6+
--------------------------------
7+
This controller wraps around ``filter_chain`` library from the `filters <https://index.ros.org/p/filters/#humble>`__ package. It allows to chain multiple filters together, where the output of one filter is the input of the next one. The controller can be used to apply a sequence of filters to a single interface, the same filter chain to multiple interfaces, or different filter chains to different interfaces.
8+
9+
10+
Parameters
11+
^^^^^^^^^^^
12+
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters. The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/chained_filter_controller/src/chained_filter_parameters.yaml>`_ contains descriptions for all the parameters used by the controller.
13+
14+
15+
Full list of parameters:
16+
17+
.. generate_parameter_library_details:: ../src/chained_filter_parameters.yaml
18+
19+
An example parameter file for this controller can be found in `the test directory <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/chained_filter_controller/test/config/test_chained_filter.yaml>`_ for a single interface:
20+
21+
.. literalinclude:: ../test/config/test_chained_filter.yaml
22+
:language: yaml
23+
24+
or for `multiple interfaces <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/chained_filter_controller/test/config/test_multiple_chained_filter.yaml>`_:
25+
26+
.. literalinclude:: ../test/config/test_multiple_chained_filter.yaml
27+
:language: yaml
Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,63 @@
1+
// Copyright 2025 ros2_control PMC
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef CHAINED_FILTER_CONTROLLER__CHAINED_FILTER_HPP_
16+
#define CHAINED_FILTER_CONTROLLER__CHAINED_FILTER_HPP_
17+
18+
#include <memory>
19+
#include <string>
20+
#include <vector>
21+
22+
#include "controller_interface/chainable_controller_interface.hpp"
23+
#include "filters/filter_chain.hpp"
24+
#include "rclcpp/rclcpp.hpp"
25+
#include "rclcpp_lifecycle/state.hpp"
26+
27+
#include "chained_filter_controller/chained_filter_parameters.hpp"
28+
29+
namespace chained_filter_controller
30+
{
31+
32+
class ChainedFilter : public controller_interface::ChainableControllerInterface
33+
{
34+
public:
35+
controller_interface::CallbackReturn on_init() override;
36+
37+
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
38+
39+
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
40+
41+
controller_interface::CallbackReturn on_configure(
42+
const rclcpp_lifecycle::State & previous_state) override;
43+
44+
controller_interface::CallbackReturn on_activate(
45+
const rclcpp_lifecycle::State & previous_state) override;
46+
47+
controller_interface::return_type update_and_write_commands(
48+
const rclcpp::Time & time, const rclcpp::Duration & period) override;
49+
50+
protected:
51+
std::vector<hardware_interface::StateInterface> on_export_state_interfaces() override;
52+
53+
controller_interface::return_type update_reference_from_subscribers(
54+
const rclcpp::Time & time, const rclcpp::Duration & period) override;
55+
56+
std::shared_ptr<chained_filter::ParamListener> param_listener_;
57+
chained_filter::Params params_;
58+
59+
std::vector<std::unique_ptr<filters::FilterChain<double>>> filters_;
60+
std::vector<double> output_state_values_;
61+
};
62+
} // namespace chained_filter_controller
63+
#endif // CHAINED_FILTER_CONTROLLER__CHAINED_FILTER_HPP_

chained_filter_controller/package.xml

Lines changed: 43 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,43 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>chained_filter_controller</name>
5+
<version>0.0.0</version>
6+
<description>ros2_controller for configuring filter chains</description>
7+
8+
<maintainer email="[email protected]">Bence Magyar</maintainer>
9+
<maintainer email="[email protected]">Denis Štogl</maintainer>
10+
<maintainer email="[email protected]">Christoph Froehlich</maintainer>
11+
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>
12+
13+
<license>Apache License 2.0</license>
14+
15+
<url type="website">https://control.ros.org</url>
16+
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
17+
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>
18+
19+
<author email="[email protected]">Bence Magyar</author>
20+
<author email="[email protected]">Christoph Froehlich</author>
21+
<author email="[email protected]">ankur-u24</author>
22+
23+
<buildtool_depend>ament_cmake</buildtool_depend>
24+
25+
<build_depend>generate_parameter_library</build_depend>
26+
<build_depend>ros2_control_cmake</build_depend>
27+
28+
<depend>controller_interface</depend>
29+
<depend>filters</depend>
30+
<depend>pluginlib</depend>
31+
<depend>rclcpp</depend>
32+
<depend>rclcpp_lifecycle</depend>
33+
<depend>hardware_interface</depend>
34+
35+
<test_depend>ament_cmake_gmock</test_depend>
36+
<test_depend>controller_manager</test_depend>
37+
<test_depend>hardware_interface_testing</test_depend>
38+
<test_depend>ros2_control_test_assets</test_depend>
39+
40+
<export>
41+
<build_type>ament_cmake</build_type>
42+
</export>
43+
</package>
Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
<library path="chained_filter_controller">
2+
<class name="chained_filter_controller/ChainedFilter"
3+
type="chained_filter_controller::ChainedFilter"
4+
base_class_type="controller_interface::ChainableControllerInterface">
5+
<description>
6+
A chainable ROS 2 controller that applies a sequence of filters to a state interface using the filters package,
7+
and exports the filtered output as a new state interface.
8+
</description>
9+
</class>
10+
</library>

0 commit comments

Comments
 (0)