diff --git a/README.md b/README.md
index 3be1354c8..8a070d0cf 100644
--- a/README.md
+++ b/README.md
@@ -475,6 +475,30 @@ Available controllers:
Commanding the robot: see the commands below.
+### Example 6: "Industrial Robots with an exposed transmission interface"
+
+Files:
+ - Launch file: [rrbot_transmissions_system_position_only.launch.py](ros2_control_demo_bringup/launch/rrbot_transmissions_system_position_only.launch.py)
+ - Controllers yaml: [rrbot_controllers.yaml](ros2_control_demo_bringup/config/rrbot_controllers.yaml)
+ - URDF: [rrbot_transmissions_system_position_only.urdf.xacro](ros2_control_demo_description/rrbot_description/urdf/rrbot_transmissions_system_position_only.urdf.xacro)
+ - `ros2_control` URDF tag: [rrbot_transmissions_system_position_only.ros2_control.xacro](ros2_control_demo_description/rrbot_description/ros2_control/rrbot_transmissions_system_position_only.ros2_control.xacro)
+
+Interfaces:
+ - Command interfaces:
+ - joint1/position
+ - joint2/position
+ - State interfaces:
+ - joint1/position
+ - joint2/position
+
+Available controllers:
+ - `joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster]`
+ - `forward_position_controller[forward_command_controller/ForwardCommandController]` (position)
+
+Moving the robot:
+ - see below description of `forward_position_controller`
+
+
## Controllers and moving hardware
To move the robot you should load and start controllers.
diff --git a/ros2_control_demo_bringup/launch/rrbot_transmissions_system_position_only.launch.py b/ros2_control_demo_bringup/launch/rrbot_transmissions_system_position_only.launch.py
new file mode 100644
index 000000000..6d3d0dca3
--- /dev/null
+++ b/ros2_control_demo_bringup/launch/rrbot_transmissions_system_position_only.launch.py
@@ -0,0 +1,70 @@
+# 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 DeclareLaunchArgument, IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir
+
+
+def generate_launch_description():
+ # Declare arguments
+ declared_arguments = []
+ declared_arguments.append(
+ DeclareLaunchArgument(
+ "prefix",
+ default_value='""',
+ description="Prefix of the joint names, useful for \
+ multi-robot setup. If changed than also joint names in the controllers' configuration \
+ have to be updated.",
+ )
+ )
+ declared_arguments.append(
+ DeclareLaunchArgument(
+ "slowdown", default_value="50.0", description="Slowdown factor of the RRbot."
+ )
+ )
+ declared_arguments.append(
+ DeclareLaunchArgument(
+ "robot_controller",
+ default_value="forward_position_controller",
+ description="Robot controller to start.",
+ )
+ )
+ declared_arguments.append(
+ DeclareLaunchArgument(
+ "start_rviz",
+ default_value="true",
+ description="Start RViz2 automatically with this launch file.",
+ )
+ )
+
+ # Initialize Arguments
+ prefix = LaunchConfiguration("prefix")
+ slowdown = LaunchConfiguration("slowdown")
+ robot_controller = LaunchConfiguration("robot_controller")
+ start_rviz = LaunchConfiguration("start_rviz")
+
+ base_launch = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource([ThisLaunchFileDir(), "/rrbot_base.launch.py"]),
+ launch_arguments={
+ "description_file": "rrbot_transmissions_system_position_only.urdf.xacro",
+ "prefix": prefix,
+ "slowdown": slowdown,
+ "robot_controller": robot_controller,
+ "start_rviz": start_rviz,
+ }.items(),
+ )
+
+ return LaunchDescription(declared_arguments + [base_launch])
diff --git a/ros2_control_demo_description/rrbot_description/ros2_control/rrbot_transmissions_system_position_only.ros2_control.xacro b/ros2_control_demo_description/rrbot_description/ros2_control/rrbot_transmissions_system_position_only.ros2_control.xacro
new file mode 100644
index 000000000..590b21c9f
--- /dev/null
+++ b/ros2_control_demo_description/rrbot_description/ros2_control/rrbot_transmissions_system_position_only.ros2_control.xacro
@@ -0,0 +1,50 @@
+
+
+
+
+
+
+
+
+ ros2_control_demo_hardware/RRBotTransmissionsSystemPositionOnlyHardware
+ ${slowdown}
+
+
+
+
+ -1
+ 1
+
+
+
+
+
+
+ -1
+ 1
+
+
+
+
+
+ transmission_interface/SimpleTransmission
+
+
+ 2.0
+ 0.0
+
+
+
+
+ transmission_interface/SimpleTransmission
+
+
+ 4.0
+ 0.0
+
+
+
+
+
+
+
diff --git a/ros2_control_demo_description/rrbot_description/urdf/rrbot_transmissions_system_position_only.urdf.xacro b/ros2_control_demo_description/rrbot_description/urdf/rrbot_transmissions_system_position_only.urdf.xacro
new file mode 100644
index 000000000..f9fd6347c
--- /dev/null
+++ b/ros2_control_demo_description/rrbot_description/urdf/rrbot_transmissions_system_position_only.urdf.xacro
@@ -0,0 +1,38 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ true
+
+
+
+
+
+
+
+
+
diff --git a/ros2_control_demo_hardware/CMakeLists.txt b/ros2_control_demo_hardware/CMakeLists.txt
index e27bb5658..4cbe811ea 100644
--- a/ros2_control_demo_hardware/CMakeLists.txt
+++ b/ros2_control_demo_hardware/CMakeLists.txt
@@ -16,6 +16,7 @@ find_package(hardware_interface REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
+find_package(transmission_interface REQUIRED)
## COMPILE
@@ -26,6 +27,7 @@ add_library(
src/rrbot_system_position_only.cpp
src/rrbot_system_multi_interface.cpp
src/rrbot_system_with_sensor.cpp
+ src/rrbot_transmissions_system_position_only.cpp
src/rrbot_actuator.cpp
src/external_rrbot_force_torque_sensor.cpp
)
@@ -40,13 +42,14 @@ ament_target_dependencies(
pluginlib
rclcpp
rclcpp_lifecycle
+ transmission_interface
)
# 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_HARDWARE_BUILDING_DLL")
-# Export hardware pligins
+# Export hardware plugins
pluginlib_export_plugin_description_file(hardware_interface ros2_control_demo_hardware.xml)
# INSTALL
@@ -75,5 +78,6 @@ ament_export_dependencies(
pluginlib
rclcpp
rclcpp_lifecycle
+ transmission_interface
)
ament_package()
diff --git a/ros2_control_demo_hardware/include/ros2_control_demo_hardware/rrbot_transmissions_system_position_only.hpp b/ros2_control_demo_hardware/include/ros2_control_demo_hardware/rrbot_transmissions_system_position_only.hpp
new file mode 100644
index 000000000..80e3692f5
--- /dev/null
+++ b/ros2_control_demo_hardware/include/ros2_control_demo_hardware/rrbot_transmissions_system_position_only.hpp
@@ -0,0 +1,96 @@
+// Copyright 2020 ros2_control Development Team
+//
+// 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 ROS2_CONTROL_DEMO_HARDWARE__RRBOT_TRANSMISSIONS_SYSTEM_POSITION_ONLY_HPP_
+#define ROS2_CONTROL_DEMO_HARDWARE__RRBOT_TRANSMISSIONS_SYSTEM_POSITION_ONLY_HPP_
+
+#include