Skip to content

Commit

Permalink
Merge branch 'master' into add-mecanum-drive-controller
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl authored Nov 18, 2024
2 parents b468bd5 + 0590c6a commit 9317768
Show file tree
Hide file tree
Showing 46 changed files with 2,650 additions and 56 deletions.
13 changes: 10 additions & 3 deletions ackermann_steering_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,17 @@
<name>ackermann_steering_controller</name>
<version>4.16.0</version>
<description>Steering controller for Ackermann kinematics. Rear fixed wheels are powering the vehicle and front wheels are steering it.</description>
<license>Apache License 2.0</license>

<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Dr.-Ing. Denis Štogl</maintainer>
<maintainer email="[email protected]">dr. sc. Tomislav Petkovic</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Christoph Froehlich</maintainer>
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>

<license>Apache License 2.0</license>

<url type="website">https://control.ros.org</url>
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>

<author email="[email protected]">Dr.-Ing. Denis Štogl</author>
<author email="[email protected]">dr. sc. Tomislav Petkovic</author>
Expand Down
15 changes: 13 additions & 2 deletions admittance_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,22 @@
<name>admittance_controller</name>
<version>4.16.0</version>
<description>Implementation of admittance controllers for different input and output interface.</description>
<maintainer email="[email protected]">Denis Štogl</maintainer>

<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Andy Zelenak</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Christoph Froehlich</maintainer>
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>

<license>Apache License 2.0</license>

<url type="website">https://control.ros.org</url>
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>

<author email="[email protected]">Denis Štogl</author>
<author email="[email protected]">Andy Zelenak</author>
<author email="[email protected]">Paul Gesel</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>backward_ros</depend>
Expand Down
13 changes: 10 additions & 3 deletions bicycle_steering_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,17 @@
<name>bicycle_steering_controller</name>
<version>4.16.0</version>
<description>Steering controller with bicycle kinematics. Rear fixed wheel is powering the vehicle and front wheel is steering.</description>
<license>Apache License 2.0</license>

<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Dr.-Ing. Denis Štogl</maintainer>
<maintainer email="[email protected]">dr. sc. Tomislav Petkovic</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Christoph Froehlich</maintainer>
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>

<license>Apache License 2.0</license>

<url type="website">https://control.ros.org</url>
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>

<author email="[email protected]">Dr.-Ing. Denis Štogl</author>
<author email="[email protected]">dr. sc. Tomislav Petkovic</author>
Expand Down
16 changes: 14 additions & 2 deletions diff_drive_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,24 @@
<package format="3">
<name>diff_drive_controller</name>
<version>4.16.0</version>
<description>Controller for a differential drive mobile base.</description>
<description>Controller for a differential-drive mobile base.</description>

<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Jordan Palacios</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Christoph Froehlich</maintainer>
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>

<license>Apache License 2.0</license>

<url type="website">https://control.ros.org</url>
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>

<author email="[email protected]">Bence Magyar</author>
<author>Enrique Fernández</author>
<author>Manuel Meraz</author>
<author email="[email protected]">Jordan Palacios</author>

<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>generate_parameter_library</build_depend>

Expand Down
1 change: 1 addition & 0 deletions doc/controllers_index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ The controllers are using `common hardware interface definitions`_, and may use
PID Controller <../pid_controller/doc/userdoc.rst>
Position Controllers <../position_controllers/doc/userdoc.rst>
Velocity Controllers <../velocity_controllers/doc/userdoc.rst>
Gpio Command Controller <../gpio_controllers/doc/userdoc.rst>


Broadcasters
Expand Down
4 changes: 4 additions & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -63,3 +63,7 @@ steering_controllers_library
tricycle_controller
************************
* tricycle_controller now uses generate_parameter_library (`#957 <https://github.com/ros-controls/ros2_controllers/pull/957>`_).

gpio_controllers
************************
* The GPIO command controller was added 🎉 (`#1251 <https://github.com/ros-controls/ros2_controllers/pull/1251>`_).
11 changes: 10 additions & 1 deletion effort_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,20 @@
<name>effort_controllers</name>
<version>4.16.0</version>
<description>Generic controller for forwarding commands.</description>

<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Jordan Palacios</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Christoph Froehlich</maintainer>
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>

<license>Apache License 2.0</license>

<url type="website">https://control.ros.org</url>
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>

<author email="[email protected]">Jordan Palacios</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>backward_ros</depend>
Expand Down
14 changes: 12 additions & 2 deletions force_torque_sensor_broadcaster/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,21 @@
<name>force_torque_sensor_broadcaster</name>
<version>4.16.0</version>
<description>Controller to publish state of force-torque sensors.</description>

<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Subhas Das</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Christoph Froehlich</maintainer>
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>

<license>Apache License 2.0</license>

<url type="website">https://control.ros.org</url>
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>

<author email="[email protected]">Denis Štogl</author>
<author email="[email protected]">Subhas Das</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>backward_ros</depend>
Expand Down
11 changes: 10 additions & 1 deletion forward_command_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,20 @@
<name>forward_command_controller</name>
<version>4.16.0</version>
<description>Generic controller for forwarding commands.</description>

<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Jordan Palacios</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Christoph Froehlich</maintainer>
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>

<license>Apache License 2.0</license>

<url type="website">https://control.ros.org</url>
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>

<author email="[email protected]">Jordan Palacios</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>backward_ros</depend>
Expand Down
115 changes: 115 additions & 0 deletions gpio_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
cmake_minimum_required(VERSION 3.8)
project(gpio_controllers)

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format -Werror=range-loop-construct
-Werror=missing-braces)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(controller_interface REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(realtime_tools REQUIRED)
find_package(generate_parameter_library REQUIRED)
find_package(control_msgs REQUIRED)


generate_parameter_library(gpio_command_controller_parameters
src/gpio_command_controller_parameters.yaml
)

add_library(gpio_controllers
SHARED
src/gpio_command_controller.cpp
)
target_include_directories(gpio_controllers PRIVATE include)
target_link_libraries(gpio_controllers PUBLIC gpio_command_controller_parameters)
ament_target_dependencies(gpio_controllers PUBLIC
builtin_interfaces
controller_interface
hardware_interface
pluginlib
rclcpp_lifecycle
rcutils
realtime_tools
control_msgs
)
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(gpio_controllers PRIVATE "GPIO_COMMAND_CONTROLLER_BUILDING_DLL")
pluginlib_export_plugin_description_file(controller_interface gpio_controllers_plugin.xml)

install(
DIRECTORY include/
DESTINATION include
)

install(
TARGETS
gpio_controllers
RUNTIME DESTINATION bin
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
)

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

ament_add_gmock(
test_load_gpio_command_controller
test/test_load_gpio_command_controller.cpp
)

target_include_directories(test_load_gpio_command_controller PRIVATE include)
ament_target_dependencies(test_load_gpio_command_controller
controller_manager
hardware_interface
ros2_control_test_assets
)

ament_add_gmock(
test_gpio_command_controller
test/test_gpio_command_controller.cpp
)
target_include_directories(test_gpio_command_controller PRIVATE include)
target_link_libraries(test_gpio_command_controller
gpio_controllers
)
ament_target_dependencies(test_gpio_command_controller
controller_interface
hardware_interface
rclcpp
rclcpp_lifecycle
realtime_tools
ros2_control_test_assets
control_msgs
)
endif()

ament_export_dependencies(
controller_interface
hardware_interface
rclcpp
rclcpp_lifecycle
realtime_tools
)
ament_export_include_directories(
include
)
ament_export_libraries(
gpio_controllers
)
ament_package()
57 changes: 57 additions & 0 deletions gpio_controllers/doc/userdoc.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
.. _gpio_controllers_userdoc:

gpio_controllers
=====================

This is a collection of controllers for hardware interfaces of type GPIO (``<gpio>`` tag in the URDF).

gpio_command_controller
-----------------------------
gpio_command_controller let the user expose command interfaces of given GPIO interfaces and publishes state interfaces of the configured command interfaces.

Description of controller's interfaces
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
- ``/<controller_name>/gpio_states`` [``control_msgs/msg/DynamicJointState``]: Publishes all state interfaces of the given GPIO interfaces.
- ``/<controller_name>/commands`` [``control_msgs/msg/DynamicJointState``]: A subscriber for configured command interfaces.


Parameters
^^^^^^^^^^^^^^^^^^^^^^^^

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}/gpio_controllers/src/gpio_command_controller_parameters.yaml>`_ contains descriptions for all the parameters used by the controller.

.. generate_parameter_library_details::
../src/gpio_command_controller_parameters.yaml

The controller expects at least one GPIO interface and the corresponding command interface names or state interface. However, these Command and State interfaces are optional. The controller behaves as a broadcaster when no Command Interface is present, thereby publishing the configured GPIO state interfaces if set, else the one present in the URDF.

.. note::

When no state interface is provided in the param file, the controller will try to use state_interfaces from ros2_control's config placed in the URDF for configured gpio interfaces.
However, command interfaces will not be configured based on the available URDF setup.

.. code-block:: yaml
gpio_command_controller:
ros__parameters:
type: gpio_controllers/GpioCommandController
gpios:
- Gpio1
- Gpio2
command_interfaces:
Gpio1:
- interfaces:
- dig.1
- dig.2
- dig.3
Gpio2:
- interfaces:
- ana.1
- ana.2
state_interfaces:
Gpio2:
- interfaces:
- ana.1
- ana.2
With the above-defined controller configuration, the controller will accept commands for all gpios' interfaces and will only publish the state of Gpio2.
7 changes: 7 additions & 0 deletions gpio_controllers/gpio_controllers_plugin.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<library path="gpio_controllers">
<class name="gpio_controllers/GpioCommandController" type="gpio_controllers::GpioCommandController" base_class_type="controller_interface::ControllerInterface">
<description>
The gpio command controller commands a group of gpios using multiple interfaces.
</description>
</class>
</library>
Loading

0 comments on commit 9317768

Please sign in to comment.