Skip to content

Commit

Permalink
Merge branch 'master' into add_simple_tests
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Sep 26, 2023
2 parents 10daa3a + 40b92dd commit fb1cdde
Show file tree
Hide file tree
Showing 29 changed files with 1,355 additions and 5 deletions.
1 change: 1 addition & 0 deletions .github/workflows/ci-coverage-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ jobs:
ros2_control_demo_example_7
ros2_control_demo_example_8
ros2_control_demo_example_9
ros2_control_demo_example_10
ros2_control_demo_example_12

vcs-repo-file-url: |
Expand Down
1 change: 1 addition & 0 deletions .github/workflows/ci-ros-lint.yml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ jobs:
ros2_control_demo_example_7
ros2_control_demo_example_8
ros2_control_demo_example_9
ros2_control_demo_example_10
ros2_control_demo_example_12

ament_lint_100:
Expand Down
22 changes: 22 additions & 0 deletions .github/workflows/iron-binary-build.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
name: Iron Binary Build
# author: Denis Štogl <denis@stoglrobotics.de>
# description: 'Build & test all dependencies from released (binary) packages.'

on:
pull_request:
branches:
- master
push:
branches:
- master
schedule:
# Run every morning to detect flakiness and broken dependencies
- cron: '03 1 * * *'

jobs:
binary:
uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml
with:
ros_distro: iron
upstream_workspace: ros2_control_demos-not-released.iron.repos
ref_for_scheduled_build: master
22 changes: 22 additions & 0 deletions .github/workflows/iron-docker-build.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
name: Build Iron Dockerfile
# description: builds the dockerfile contained within the repo

on:
pull_request:
branches:
- master
push:
branches:
- master
schedule:
# Run every morning to detect broken dependencies
- cron: '50 1 * * *'


jobs:
build:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- name: Build the Docker image
run: docker build . --file Dockerfile/Dockerfile --tag ros2_control_demos_iron
21 changes: 21 additions & 0 deletions .github/workflows/iron-semi-binary-build.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
name: Iron Semi-Binary Build
# description: 'Build & test that compiles the main dependencies from source.'

on:
pull_request:
branches:
- master
push:
branches:
- master
schedule:
# Run every morning to detect flakiness and broken dependencies
- cron: '33 1 * * *'

jobs:
semi_binary:
uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml
with:
ros_distro: iron
upstream_workspace: ros2_control_demos.iron.repos
ref_for_scheduled_build: master
6 changes: 4 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@ The following examples are part of this demo repository:

*RRBot* with an integrated sensor.


* Example 5: ["Industrial robots with externally connected sensor"](example_5)

*RRBot* with an externally connected sensor.
Expand All @@ -52,7 +51,9 @@ The following examples are part of this demo repository:

Demonstrates how to switch between simulation and hardware.

* Example 10: "RRbot with GPIO interfaces (tba.)"
* Example 10: ["Industrial robot with GPIO interfaces"](example_10)

*RRBot* with GPIO interfaces.

* Example 11: "Car-like robot using steering controller library (tba.)"

Expand Down Expand Up @@ -95,6 +96,7 @@ Those two world-known imaginary robots are trivial simulations to demonstrate an
ROS 2 Distro | Branch | Build status | Documentation
:----------: | :----: | :----------: | :-----------:
**Rolling** | [`master`](https://github.com/ros-controls/ros2_control_demos/tree/rolling) | [![Rolling Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-binary-build.yml?branch=master) <br /> [![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-semi-binary-build.yml?branch=master) <br /> | [Documentation](https://control.ros.org/master/index.html) <br /> [API Reference](https://control.ros.org/master/doc/api/index.html)
**Iron** | [`master`](https://github.com/ros-controls/ros2_control_demos/tree/master) | [![Iron Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/iron-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/iron-binary-build.yml?branch=master) <br /> [![Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/iron-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/iron-semi-binary-build.yml?branch=master) <br /> | [Documentation](https://control.ros.org/iron/index.html) <br /> [API Reference](https://control.ros.org/iron/doc/api/index.html)
**Humble** | [`humble`](https://github.com/ros-controls/ros2_control_demos/tree/humble) | [![Humble Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/humble-binary-build.yml/badge.svg?branch=humble)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/humble-binary-build.yml?branch=humble) <br /> [![Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/humble-semi-binary-build.yml/badge.svg?branch=humble)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/humble-semi-binary-build.yml?branch=humble) <br /> | [Documentation](https://control.ros.org/humble/index.html) <br /> [API Reference](https://control.ros.org/humble/doc/api/index.html)
**Galactic** | [`galactic`](https://github.com/ros-controls/ros2_control_demos/tree/galactic) | [![Galactic Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/galactic-binary-build.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/galactic-binary-build.yml?branch=galactic) <br /> [![Galactic Semi-Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/galactic-semi-binary-build.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/galactic-semi-binary-build.yml?branch=galactic) <br /> | [Documentation](https://control.ros.org/galactic/index.html) <br /> [API Reference](https://control.ros.org/galactic/doc/api/index.html)
**Foxy** | [`foxy`](https://github.com/ros-controls/ros2_control_demos/tree/foxy) | [![Foxy Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/foxy-binary-build.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/foxy-binary-build.yml?branch=foxy) <br /> [![Foxy Semi-Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/foxy-semi-binary-build.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/foxy-semi-binary-build.yml?branch=foxy) <br /> | [Documentation](https://control.ros.org/foxy/index.html) <br /> [API Reference](https://control.ros.org/foxy/doc/api/index.html)
Expand Down
4 changes: 4 additions & 0 deletions doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,9 @@ Example 8: "Using transmissions"
Example 9: "Gazebo Classic"
Demonstrates how to switch between simulation and hardware.

Example 10: "GPIO interfaces"
Industrial robot with GPIO interfaces

Example 12: "Controller chaining"
The example shows a simple chainable controller and its integration to form a controller chain to control the joints of *RRBot*.

Expand Down Expand Up @@ -259,4 +262,5 @@ Examples
Example 7: Full tutorial with a 6DOF robot <../example_7/doc/userdoc.rst>
Example 8: Using transmissions <../example_8/doc/userdoc.rst>
Example 9: Gazebo classic <../example_9/doc/userdoc.rst>
Example 10: Industrial robot with GPIO interfaces <../example_10/doc/userdoc.rst>
Example 12: Controller chaining <../example_12/doc/userdoc.rst>
5 changes: 3 additions & 2 deletions example_1/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ The *RRBot* URDF files can be found in the ``description/urdf`` folder.
Tutorial steps
--------------------------

1. To check that *RRBot* descriptions are working properly use following launch commands
1. (Optional) To check that *RRBot* descriptions are working properly use following launch commands

.. code-block:: shell
Expand All @@ -50,6 +50,7 @@ Tutorial steps
rviz2 --display-config `ros2 pkg prefix ros2_control_demo_example_1`/share/ros2_control_demo_example_1/rviz/rrbot.rviz
Once it is working you can stop rviz using CTRL+C as the next launch file is starting RViz.
2. To start *RRBot* example open a terminal, source your ROS2-workspace and execute its launch file with

Expand All @@ -61,7 +62,7 @@ Tutorial steps
In starting terminal you will see a lot of output from the hardware implementation showing its internal states.
This is only of exemplary purposes and should be avoided as much as possible in a hardware interface implementation.

If you can see two orange and one yellow rectangle in in *RViz* everything has started properly.
If you can see two orange and one yellow rectangle in *RViz* everything has started properly.
Still, to be sure, let's introspect the control system before moving *RRBot*.

3. Check if the hardware interface loaded properly, by opening another terminal and executing
Expand Down
84 changes: 84 additions & 0 deletions example_10/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
cmake_minimum_required(VERSION 3.16)
project(ros2_control_demo_example_10 LANGUAGES CXX)

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

# find dependencies
set(THIS_PACKAGE_INCLUDE_DEPENDS
hardware_interface
control_msgs
std_msgs
pluginlib
rclcpp
rclcpp_lifecycle
controller_interface
)

# find dependencies
find_package(ament_cmake REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()


## COMPILE
add_library(
ros2_control_demo_example_10
SHARED
hardware/rrbot.cpp
controllers/gpio_controller.cpp
)
target_compile_features(ros2_control_demo_example_10 PUBLIC cxx_std_17)
target_include_directories(ros2_control_demo_example_10 PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/controllers/include>
$<INSTALL_INTERFACE:include/ros2_control_demo_example_10>
)
ament_target_dependencies(
ros2_control_demo_example_10 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(${PROJECT_NAME} PRIVATE "ROS2_CONTROL_DEMO_EXAMPLE_10_BUILDING_DLL")

# Export hardware plugins
pluginlib_export_plugin_description_file(hardware_interface ros2_control_demo_example_10.xml)
# Export controllers
pluginlib_export_plugin_description_file(controller_interface ros2_control_demo_example_10.xml)

# INSTALL
install(
DIRECTORY hardware/include/
DESTINATION include/ros2_control_demo_example_10
)
install(
DIRECTORY controllers/include/
DESTINATION include/ros2_control_demo_example_10
)
install(
DIRECTORY description/launch description/ros2_control description/urdf
DESTINATION share/ros2_control_demo_example_10
)
install(
DIRECTORY bringup/launch bringup/config
DESTINATION share/ros2_control_demo_example_10
)
install(TARGETS ros2_control_demo_example_10
EXPORT export_ros2_control_demo_example_10
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
endif()

## EXPORTS
ament_export_targets(export_ros2_control_demo_example_10 HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
5 changes: 5 additions & 0 deletions example_10/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# ros2_control_demo_example_10

*RRBot* - or ''Revolute-Revolute Manipulator Robot'' - with GPIO interfaces.

Find the documentation in [doc/userdoc.rst](doc/userdoc.rst) or on [control.ros.org](https://control.ros.org/master/doc/ros2_control_demos/example_10/doc/userdoc.html).
31 changes: 31 additions & 0 deletions example_10/bringup/config/rrbot_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
controller_manager:
ros__parameters:
update_rate: 1 # Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

forward_position_controller:
type: forward_command_controller/ForwardCommandController

gpio_controller:
type: ros2_control_demo_example_10/GPIOController


forward_position_controller:
ros__parameters:
joints:
- joint1
- joint2
interface_name: position

gpio_controller:
ros__parameters:
inputs:
- flange_analog_IOs/analog_output1
- flange_analog_IOs/analog_input1
- flange_analog_IOs/analog_input2
- flange_vacuum/vacuum
outputs:
- flange_analog_IOs/analog_output1
- flange_vacuum/vacuum
11 changes: 11 additions & 0 deletions example_10/bringup/config/rrbot_forward_position_publisher.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
publisher_forward_position_controller:
ros__parameters:

wait_sec_between_publish: 5
publish_topic: "/forward_position_controller/commands"

goal_names: ["pos1", "pos2", "pos3", "pos4"]
pos1: [0.785, 0.785]
pos2: [0, 0]
pos3: [-0.785, -0.785]
pos4: [0, 0]
97 changes: 97 additions & 0 deletions example_10/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
# Copyright 2021 Stogl Robotics Consulting UG (haftungsbeschränkt)
#
# 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.


from launch import LaunchDescription
from launch.actions import RegisterEventHandler
from launch.event_handlers import OnProcessExit
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution

from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
# Get URDF via xacro
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[
FindPackageShare("ros2_control_demo_example_10"),
"urdf",
"rrbot.urdf.xacro",
]
),
]
)
robot_description = {"robot_description": robot_description_content}

robot_controllers = PathJoinSubstitution(
[
FindPackageShare("ros2_control_demo_example_10"),
"config",
"rrbot_controllers.yaml",
]
)

control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
output="both",
)
robot_state_pub_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description],
)

joint_state_broadcaster_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"],
)

robot_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["forward_position_controller", "-c", "/controller_manager"],
)

gpio_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["gpio_controller", "-c", "/controller_manager"],
)

# Delay start of robot_controller after `joint_state_broadcaster`
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)

nodes = [
control_node,
robot_state_pub_node,
joint_state_broadcaster_spawner,
gpio_controller_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]

return LaunchDescription(nodes)
Loading

0 comments on commit fb1cdde

Please sign in to comment.