Skip to content

Commit 630db23

Browse files
committed
Rewrote IO Gripper Controller to GPIO Tool Controller.
1 parent e60b083 commit 630db23

24 files changed

+1975
-2120
lines changed

gpio_controllers/CMakeLists.txt

Lines changed: 49 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -7,34 +7,59 @@ export_windows_symbols()
77

88
# find dependencies
99
find_package(ament_cmake REQUIRED)
10+
find_package(control_msgs REQUIRED)
1011
find_package(controller_interface REQUIRED)
12+
find_package(generate_parameter_library REQUIRED)
1113
find_package(hardware_interface REQUIRED)
1214
find_package(pluginlib REQUIRED)
1315
find_package(rclcpp REQUIRED)
1416
find_package(rclcpp_lifecycle REQUIRED)
1517
find_package(realtime_tools REQUIRED)
16-
find_package(generate_parameter_library REQUIRED)
17-
find_package(control_msgs REQUIRED)
18+
find_package(sensor_msgs REQUIRED)
19+
find_package(std_srvs REQUIRED)
1820

1921
generate_parameter_library(gpio_command_controller_parameters
2022
src/gpio_command_controller_parameters.yaml
2123
)
2224

23-
add_library(gpio_controllers
24-
SHARED
25+
add_library(gpio_controllers SHARED
2526
src/gpio_command_controller.cpp
2627
)
2728
target_include_directories(gpio_controllers PRIVATE include)
28-
target_link_libraries(gpio_controllers PUBLIC
29-
gpio_command_controller_parameters
29+
target_link_libraries(gpio_controllers PUBLIC gpio_command_controller_parameters)
30+
ament_target_dependencies(gpio_controllers PUBLIC
31+
builtin_interfaces
32+
controller_interface
33+
hardware_interface
34+
pluginlib
35+
rclcpp_lifecycle
36+
rcutils
37+
realtime_tools
38+
control_msgs
39+
)
40+
41+
generate_parameter_library(gpio_tool_controller_parameters
42+
src/gpio_tool_controller.yaml
43+
)
44+
add_library(gpio_tool_controllers SHARED
45+
src/gpio_tool_controller.cpp
46+
)
47+
target_compile_features(gpio_tool_controllers PUBLIC cxx_std_20)
48+
target_include_directories(gpio_tool_controllers PUBLIC
49+
"$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>"
50+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
51+
target_link_libraries(gpio_tool_controllers PUBLIC
52+
gpio_tool_controller_parameters
3053
controller_interface::controller_interface
3154
hardware_interface::hardware_interface
3255
pluginlib::pluginlib
3356
rclcpp::rclcpp
3457
rclcpp_lifecycle::rclcpp_lifecycle
3558
realtime_tools::realtime_tools
3659
${control_msgs_TARGETS}
37-
${builtin_interfaces_TARGETS})
60+
${builtin_interfaces_TARGETS}
61+
${std_srvs_TARGETS}
62+
)
3863

3964
pluginlib_export_plugin_description_file(controller_interface gpio_controllers_plugin.xml)
4065

@@ -46,6 +71,7 @@ install(
4671
install(
4772
TARGETS
4873
gpio_controllers
74+
gpio_tool_controllers
4975
RUNTIME DESTINATION bin
5076
ARCHIVE DESTINATION lib
5177
LIBRARY DESTINATION lib
@@ -78,6 +104,21 @@ if(BUILD_TESTING)
78104
gpio_controllers
79105
ros2_control_test_assets::ros2_control_test_assets
80106
)
107+
108+
# ament_add_gmock(test_gpio_tool_controller
109+
# test/gpio_tool_controller/test_gpio_tool_controller.cpp
110+
# test/gpio_tool_controller/test_gpio_tool_controller_open.cpp
111+
# test/gpio_tool_controller/test_gpio_tool_controller_close.cpp
112+
# test/gpio_tool_controller/test_gpio_tool_controller_all_param_set.cpp
113+
# test/gpio_tool_controller/test_gpio_tool_controller_open_close_action.cpp
114+
# test/gpio_tool_controller/test_gpio_tool_controller_reconfigure.cpp
115+
# test/gpio_tool_controller/test_gpio_tool_controller_reconfigure_action.cpp
116+
# )
117+
# target_include_directories(test_gpio_tool_controller PRIVATE include)
118+
# target_link_libraries(test_gpio_tool_controller
119+
# gpio_tool_controller
120+
# ros2_control_test_assets::ros2_control_test_assets
121+
# )
81122
endif()
82123

83124
ament_export_dependencies(
@@ -92,5 +133,6 @@ ament_export_include_directories(
92133
)
93134
ament_export_libraries(
94135
gpio_controllers
136+
gpio_tool_controllers
95137
)
96138
ament_package()

gpio_controllers/gpio_controllers_plugin.xml

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,3 +5,12 @@
55
</description>
66
</class>
77
</library>
8+
9+
<library path="gpio_tool_controllers">
10+
<class name="gpio_tool_controller/GpioToolController" type="gpio_tool_controller::GpioToolController" base_class_type="controller_interface::ControllerInterface">
11+
<description>
12+
The gpio tool controllers enables control of the tools that are controlled using GPIOs. For example, pneumatic grippers, lifts, etc. It enables management of multiple engaged state, e.g., if gripper is closed with or without an object.
13+
The controller can be also be used in the simple form where certian states of a device are set through GPIOs, e.g., manual and automatic mode.
14+
</description>
15+
</class>
16+
</library>

0 commit comments

Comments
 (0)