Skip to content

Commit

Permalink
Merge branch 'master' into pr147_rebase
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Aug 11, 2023
2 parents 86c507b + 2968016 commit d80f6e2
Show file tree
Hide file tree
Showing 26 changed files with 1,844 additions and 2 deletions.
4 changes: 3 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,9 @@ The following examples are part of this demo repository:

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

* Example 12: "Controller chaining example (tba.)"
* Example 12: ["Controller chaining"](example_12)

The example shows a simple chainable controller and its integration to form a controller chain to control the joints of *RRBot*.

* Example 13: "Multi-robot example (tba.)"

Expand Down
5 changes: 4 additions & 1 deletion doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,8 @@ Example 10: "RRbot with GPIO interfaces (tba.)"

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

Example 12: "Controller chaining example (tba.)"
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*.

Example 13: "Multi-robot example (tba.)"

Expand Down Expand Up @@ -264,4 +265,6 @@ 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 12: Controller chaining <../example_12/doc/userdoc.rst>
Example 14: Modular robots with actuators not providing states <../example_14/doc/userdoc.rst>

115 changes: 115 additions & 0 deletions example_12/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
cmake_minimum_required(VERSION 3.16)
project(ros2_control_demo_example_12 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
pluginlib
rclcpp
rclcpp_lifecycle
control_msgs
generate_parameter_library
controller_interface
parameter_traits
realtime_tools
std_msgs
)

# 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_12
SHARED
hardware/rrbot.cpp
)
target_compile_features(ros2_control_demo_example_12 PUBLIC cxx_std_17)
target_include_directories(ros2_control_demo_example_12 PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/hardware/include>
$<INSTALL_INTERFACE:include/ros2_control_demo_example_12>
)
ament_target_dependencies(
ros2_control_demo_example_12 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_9_BUILDING_DLL")

# Export hardware plugins
pluginlib_export_plugin_description_file(hardware_interface ros2_control_demo_example_12.xml)

# Add library of the controller and export it
generate_parameter_library(passthrough_controller_parameters
controllers/src/passthrough_controller_parameters.yaml
)

add_library(passthrough_controller SHARED
controllers/src/passthrough_controller.cpp
)
target_include_directories(passthrough_controller PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/controllers/include>
$<INSTALL_INTERFACE:include/passthrough_controller>
)
target_link_libraries(passthrough_controller PUBLIC passthrough_controller_parameters)
ament_target_dependencies(passthrough_controller 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(passthrough_controller PRIVATE "passthrough_controller_BUILDING_DLL")

pluginlib_export_plugin_description_file(controller_interface passthrough_controller.xml)


# INSTALL
install(
DIRECTORY hardware/include/
DESTINATION include/ros2_control_demo_example_12
)
install(
DIRECTORY description/launch description/ros2_control description/urdf description/gazebo description/rviz
DESTINATION share/ros2_control_demo_example_12
)
install(
DIRECTORY bringup/launch bringup/config
DESTINATION share/ros2_control_demo_example_12
)
install(TARGETS ros2_control_demo_example_12
EXPORT export_ros2_control_demo_example_12
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(
DIRECTORY controllers/include/
DESTINATION include/passthrough_controller
)

install(TARGETS
passthrough_controller
passthrough_controller_parameters
EXPORT export_passthrough_controller
RUNTIME DESTINATION bin
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
)

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

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

This example demonstrates the switching between simulation and real hardware by means of the *RRBot* - or ''Revolute-Revolute Manipulator Robot''.

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_12/doc/userdoc.html).
44 changes: 44 additions & 0 deletions example_12/bringup/config/rrbot_chained_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
controller_manager:
ros__parameters:
update_rate: 10 # Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

joint1_position_controller:
type: passthrough_controller/PassthroughController

joint2_position_controller:
type: passthrough_controller/PassthroughController

position_controller:
type: passthrough_controller/PassthroughController

forward_position_controller:
type: forward_command_controller/ForwardCommandController

# First-level controllers
joint1_position_controller:
ros__parameters:
interfaces: ["joint1/position"]


joint2_position_controller:
ros__parameters:
interfaces: ["joint2/position"]


# Second-level controller
position_controller:
ros__parameters:
interfaces:
- joint1_position_controller/joint1/position
- joint2_position_controller/joint2/position

# Third-level controllers
forward_position_controller:
ros__parameters:
joints:
- position_controller/joint1_position_controller/joint1
- position_controller/joint2_position_controller/joint2
interface_name: position
51 changes: 51 additions & 0 deletions example_12/bringup/launch/launch_chained_controllers.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
# 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_ros.actions import Node


def generate_launch_description():

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

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

# Delay start of forward_position_controller_spawner after `position_controller_spawner`
delay_forward_position_controller_spawner_after_position_controller_spawner = (
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=position_controller_spawner,
on_exit=[forward_position_controller_spawner],
)
)
)

nodes = [
position_controller_spawner,
delay_forward_position_controller_spawner_after_position_controller_spawner,
]

return LaunchDescription(nodes)
115 changes: 115 additions & 0 deletions example_12/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
# 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_12"),
"urdf",
"rrbot.urdf.xacro",
]
),
]
)
robot_description = {"robot_description": robot_description_content}

robot_controllers = PathJoinSubstitution(
[
FindPackageShare("ros2_control_demo_example_12"),
"config",
"rrbot_chained_controllers.yaml",
]
)
rviz_config_file = PathJoinSubstitution(
[FindPackageShare("ros2_control_demo_example_12"), "rviz", "rrbot.rviz"]
)

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],
)
rviz_node = Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", rviz_config_file],
)

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

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

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

# Delay rviz start after `joint_state_broadcaster`
delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[rviz_node],
)
)

# 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=[j1_controller_spawner, j2_controller_spawner],
)
)

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

return LaunchDescription(nodes)
Loading

0 comments on commit d80f6e2

Please sign in to comment.