diff --git a/README.md b/README.md index 88ff1c509..3be1354c8 100644 --- a/README.md +++ b/README.md @@ -2,60 +2,49 @@ [![Licence](https://img.shields.io/badge/License-Apache%202.0-blue.svg)](https://opensource.org/licenses/Apache-2.0) -This repository provides templates for the development of `ros2_control`-enabled robots and a simple simulations to demonstrate and prove `ros2_control` concepts. +This repository provides examples for functionalities and capabilities of `ros2_control` framework. +It consists of simple implementations that demonstrate different concepts. -### First-Time Users - -If you're just starting out, we suggest to look at the minimal example: `ros2_control_demo_bringup/launch/rrbot_system_position_only.launch.py`. - -Also pay attention to these files: - -- `ros2_control_demo_description/rrbot_description/ros2_control/rrbot_system_position_only.ros2_control.xacro` -- this file defines the ros2_control interfaces for each joint, e.g. position or velocity. The simulation can be launched with Gazebo or simulated with RViz only. -- `rrbot_controllers.yaml` -- list the controllers that will be launched. +If you want to have rather step by step manual how to do things with `ros2_control` checkout [ros-control/roscon2022_workshop](https://github.com/ros-controls/roscon2022_workshop) repository. ### Goals -The repository has three goals: +The repository has two other goals goals: + 1. Implements the example configuration described in the `ros-controls/roadmap` repository file [components_architecture_and_urdf_examples](https://github.com/ros-controls/roadmap/blob/master/design_drafts/components_architecture_and_urdf_examples.md). -2. It provides templates for faster implementation of custom hardware and controllers; -3. The repository is a validation environment for `ros2_control` concepts, which can only be tested during run-time (e.g., execution of controllers by the controller manager, communication between robot hardware and controllers). +2. The repository is a validation environment for `ros2_control` concepts, which can only be tested during run-time (e.g., execution of controllers by the controller manager, communication between robot hardware and controllers). -## Build status +## Getting started -ROS2 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)
[![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)
[![Rolling Source Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-source-build.yml?branch=master) | [Documentation](https://control.ros.org)
[API Reference](https://control.ros.org/rolling/api/) -**Rolling - last Focal** | [`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-last-focal.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-binary-build-last-focal.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-semi-binary-build-last-focal.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-semi-binary-build-last-focal.yml?branch=master) | [Documentation](https://control.ros.org)
[API Reference](https://control.ros.org/rolling/api/) -**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)
[![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)
[![Galactic Source Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/galactic-source-build.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/galactic-source-build.yml?branch=galactic) | [Documentation](https://control.ros.org)
[API Reference](https://control.ros.org/rolling/api/) -**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)
[![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)
[![Foxy Source Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/foxy-source-build.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/foxy-source-build.yml?branch=foxy) | [Documentation](https://control.ros.org)
[API Reference](https://control.ros.org/rolling/api/) +The repository is structured into `example_XY` folders that fully contained packages with names `ros2_control_demos_example_XY`. -### Explanation of different build types +The packages have following structure of subfolders: -**NOTE**: There are three build stages checking current and future compatibility of the package. +- `bringup` - stores launch files and runtime configurations for demo robots. +- `description` - stores URDF (and XACRO) description files, rviz configurations and meshes for the example robots. +- `hardware` - stores implementations of example hardware components (interfaces). +- `controllers` (optional) - stores implementation of example controllers. -1. Binary builds - against released packages (main and testing) in ROS distributions. Shows that direct local build is possible. +The important files to check in each example are: - Uses repos file: `src/$NAME$/$NAME$-not-released..repos` - -1. Semi-binary builds - against released core ROS packages (main and testing), but the immediate dependencies are pulled from source. - Shows that local build with dependencies is possible and if fails there we can expect that after the next package sync we will not be able to build. - - Uses repos file: `src/$NAME$/$NAME$.repos` - -1. Source build - also core ROS packages are build from source. It shows potential issues in the mid future. +- `bringup/launch/.launch.py` - launch file for the example +- `bringup/config/_controllers.yaml` - parameters with controllers' setup for the example. +- `description/.ros2_control.xacro` - XACRO file with `ros2_control`-URDF-tag with hardware setup and parameters. +- `description/.urdf.xacro` - the main description for for the example used to generate URDF on the fly that is published on the `/robot_description` topic. +- `hardware/.hpp` - header file of the example hardware component implementation. +- `hardware/.cpp` - source file with the example hardware component implementation. +- `controllers/.hpp` - header file of the example controller implementation. +- `controllers/.cpp` - source file with the example controller implementation. +**NOTE** - The structure of packages, folders and files given in this repository is not recommended to be used for your robot. Usually you should have all of the above folders defined as separate packages with naming convention `/[bringup|description|hardware|controllers]`. + More standard structure can be found in [ros_control_boilerplate](https://github.com/PickNikRobotics/ros_control_boilerplate) repository from Dave Coleman or documentation on [ros_team_workspace](https://rtw.stoglrobotics.de/master/guidelines/robot_package_structure.html) from Stogl Robotics. -## Description +The concepts in this package are demonstrated on the examples of *RRBot* and *DiffBot*. +Those two world-known imaginary robots are trivial simulations to demonstrate and test `ros2_control` concepts. -The repository is inspired by the [ros_control_boilerplate](https://github.com/PickNikRobotics/ros_control_boilerplate) repository from Dave Coleman. -The examples have three parts/packages according to usual structure of ROS packages for robots: -1. The bringup package `ros2_control_demo_bringup`, holds launch files and runtime configurations for demo robots. -2. Description packages `rrbot_description` and `diffbot_description` (inside `ros2_control_demo_description`), store URDF-description files, rviz configurations and meshes for the demo robots. -3. Hardware interface package `ros2_control_demo_hardware`, implements the hardware interfaces described in the roadmap. -The examples of *RRBot* and *DiffBot* are trivial simulations to demonstrate and test `ros2_control` concepts. -This package does not have any dependencies except `ros2` core packages and can, therefore, be used on SoC-hardware or headless systems. +## What you can Find in This Repository and Example Description This repository demonstrates the following `ros2_control` concepts: @@ -68,6 +57,21 @@ This repository demonstrates the following `ros2_control` concepts: * Implementing a controller switching strategy for a robot. * Using joint limits and transmission concepts in `ros2_control`. + +### Example Overview + +Check README file inside each example folder for detailed description. + +##### Example 1 + +*RRBot* - or ''Revolute-Revolute Manipulator Robot'' - a simple position controlled robot with one hardware interface. + + +##### Example 2 + +.... + + ## Quick Hints These are some quick hints, especially for those coming from a ROS1 control background: @@ -84,6 +88,32 @@ These are some quick hints, especially for those coming from a ROS1 control back The ros2_control framework uses the **** tag in the URDF. * Joint names in tags in the URDF must be compatible with the controller's configuration. + +## Build status + +ROS2 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)
[![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)
[![Rolling Source Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-source-build.yml?branch=master) | [Documentation](https://control.ros.org)
[API Reference](https://control.ros.org/rolling/api/) +**Rolling - last Focal** | [`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-last-focal.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-binary-build-last-focal.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-semi-binary-build-last-focal.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/rolling-semi-binary-build-last-focal.yml?branch=master) | [Documentation](https://control.ros.org)
[API Reference](https://control.ros.org/rolling/api/) +**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)
[![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)
[![Galactic Source Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/galactic-source-build.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/galactic-source-build.yml?branch=galactic) | [Documentation](https://control.ros.org)
[API Reference](https://control.ros.org/rolling/api/) +**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)
[![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)
[![Foxy Source Build](https://github.com/ros-controls/ros2_control_demos/actions/workflows/foxy-source-build.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control_demos/actions/workflows/foxy-source-build.yml?branch=foxy) | [Documentation](https://control.ros.org)
[API Reference](https://control.ros.org/rolling/api/) + +### Explanation of different build types + +**NOTE**: There are three build stages checking current and future compatibility of the package. + +1. Binary builds - against released packages (main and testing) in ROS distributions. Shows that direct local build is possible. + + Uses repos file: `src/$NAME$/$NAME$-not-released..repos` + +1. Semi-binary builds - against released core ROS packages (main and testing), but the immediate dependencies are pulled from source. + Shows that local build with dependencies is possible and if fails there we can expect that after the next package sync we will not be able to build. + + Uses repos file: `src/$NAME$/$NAME$.repos` + +1. Source build - also core ROS packages are build from source. It shows potential issues in the mid future. + + # Build from source ``` git clone https://github.com/ros-controls/ros2_control @@ -114,91 +144,6 @@ This repository provides the following simple example robots: a 2 degrees of fre The first two examples demonstrate the minimal setup for those two robots to run. Later examples show more details about `ros2_control`-concepts and some more advanced use-cases. -## *RRBot* - -*RRBot*, or ''Revolute-Revolute Manipulator Robot'', is a simple 3-linkage, 2-joint arm that we will use to demonstrate various features. -It is essentially a double inverted pendulum and demonstrates some fun control concepts within a simulator and was originally introduced for Gazebo tutorials. -The *RRBot* URDF files can be found in the `urdf` folder of `rrbot_description` package. - -1. To check that *RRBot* descriptions are working properly use following launch commands: - - *RRBot* - ``` - ros2 launch rrbot_description view_robot.launch.py - ``` - **NOTE**: Getting the following output in terminal is OK: `Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist`. - This happens because `joint_state_publisher_gui` node need some time to start. - The `joint_state_publisher_gui` provides a GUI to generate a random configuration for rrbot. It is immediately displayed in `Rviz`. - - -1. To start *RRBot* example open a terminal, source your ROS2-workspace and execute its launch file with: - ``` - ros2 launch ros2_control_demo_bringup rrbot.launch.py - ``` - The launch file loads and starts the robot hardware, controllers and opens `RViz`. - 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. - Still, to be sure, let's introspect the control system before moving *RRBot*. - -1. Check if the hardware interface loaded properly, by opening another terminal and executing: - ``` - ros2 control list_hardware_interfaces - ``` - You should get: - ``` - command interfaces - joint1/position [claimed] - joint2/position [claimed] - state interfaces - joint1/position - joint2/position - - ``` - Marker `[claimed]` by command interfaces means that a controller has access to command *RRBot*. - -1. Check is controllers are running: - ``` - ros2 control list_controllers - ``` - You should get: - ``` - joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active - forward_position_controller[forward_command_controller/ForwardCommandController] active - ``` - -1. If you get output from above you can send commands to *Forward Command Controller*, either: - - a. Manually using ros2 cli interface: - ``` - ros2 topic pub /position_commands std_msgs/msg/Float64MultiArray "data: - - 0.5 - - 0.5" - ``` - B. Or you can start a demo node which sends two goals every 5 seconds in a loop: - ``` - ros2 launch ros2_control_demo_bringup test_forward_position_controller.launch.py - ``` - You should now see orange and yellow blocks moving in `RViz`. - Also, you should see changing states in the terminal where launch file is started. - - -Files used for this demos: - - Launch file: [rrbot.launch.py](ros2_control_demo_bringup/launch/rrbot.launch.py) - - Controllers yaml: [rrbot_controllers.yaml](ros2_control_demo_bringup/config/rrbot_controllers.yaml) - - URDF file: [rrbot.urdf.xacro](ros2_control_demo_description/rrbot_description/urdf/rrbot.urdf.xacro) - - Description: [rrbot_description.urdf.xacro](ros2_control_demo_description/rrbot_description/urdf/rrbot_description.urdf.xacro) - - `ros2_control` tag: [rrbot.ros2_control.xacro](ros2_control_demo_description/rrbot_description/ros2_control/rrbot.ros2_control.xacro) - - RViz configuration: [rrbot.rviz](ros2_control_demo_description/rrbot_description/config/rrbot.rviz) - - - Hardware interface plugin: [rrbot_system_position_only.cpp](ros2_control_demo_hardware/src/rrbot_system_position_only.cpp) - - -Controllers from this demo: - - `Joint State Broadcaster` ([`ros2_controllers` repository](https://github.com/ros-controls/ros2_controllers)): [doc](https://ros-controls.github.io/control.ros.org/ros2_controllers/joint_state_broadcaster/doc/userdoc.html) - - `Forward Command Controller` ([`ros2_controllers` repository](https://github.com/ros-controls/ros2_controllers)): [doc](https://ros-controls.github.io/control.ros.org/ros2_controllers/forward_command_controller/doc/userdoc.html) - ## *DiffBot* diff --git a/example_1/CMakeLists.txt b/example_1/CMakeLists.txt new file mode 100644 index 000000000..24d91c90a --- /dev/null +++ b/example_1/CMakeLists.txt @@ -0,0 +1,74 @@ +cmake_minimum_required(VERSION 3.5) +project(ros2_control_demo_hardware) + +# 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) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(hardware_interface REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) + + +## COMPILE +add_library( + ${PROJECT_NAME} + SHARED + hardware/rrbot.cpp +) +target_include_directories( + ${PROJECT_NAME} + PRIVATE + include +) +ament_target_dependencies( + ${PROJECT_NAME} + hardware_interface + pluginlib + rclcpp + rclcpp_lifecycle +) + +# 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 +pluginlib_export_plugin_description_file(hardware_interface ros2_control_demo_hardware.xml) + +# INSTALL +install( + TARGETS ${PROJECT_NAME} + DESTINATION lib +) +install( + DIRECTORY include/ + DESTINATION include +) + +if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) +endif() + +## EXPORTS +ament_export_include_directories( + include +) +ament_export_libraries( + ${PROJECT_NAME} +) +ament_export_dependencies( + hardware_interface + pluginlib + rclcpp + rclcpp_lifecycle +) +ament_package() diff --git a/example_1/README.rst b/example_1/README.rst new file mode 100644 index 000000000..5e4db7b46 --- /dev/null +++ b/example_1/README.rst @@ -0,0 +1,98 @@ + + +TODO(destogl): This is not adjusted yet!! + + +*RRBot*, or ''Revolute-Revolute Manipulator Robot'', is a simple 3-linkage, 2-joint arm that we will use to demonstrate various features. +It is essentially a double inverted pendulum and demonstrates some fun control concepts within a simulator and was originally introduced for Gazebo tutorials. +The *RRBot* URDF files can be found in the `urdf` folder of `rrbot_description` package. + +1. To check that *RRBot* descriptions are working properly use following launch commands: + + *RRBot* + ``` + ros2 launch rrbot_description view_robot.launch.py + ``` + **NOTE**: Getting the following output in terminal is OK: `Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist`. + This happens because `joint_state_publisher_gui` node need some time to start. + The `joint_state_publisher_gui` provides a GUI to generate a random configuration for rrbot. It is immediately displayed in `Rviz`. + + +1. To check that *RRBot* descriptions are working properly use following launch commands: + + *RRBot* + ``` + ros2 launch rrbot_description view_robot.launch.py + ``` + **NOTE**: Getting the following output in terminal is OK: `Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist`. + This happens because `joint_state_publisher_gui` node need some time to start. + The `joint_state_publisher_gui` provides a GUI to generate a random configuration for rrbot. It is immediately displayed in `Rviz`. + + +1. To start *RRBot* example open a terminal, source your ROS2-workspace and execute its launch file with: + ``` + ros2 launch ros2_control_demo_bringup rrbot.launch.py + ``` + The launch file loads and starts the robot hardware, controllers and opens `RViz`. + 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. + Still, to be sure, let's introspect the control system before moving *RRBot*. + +1. Check if the hardware interface loaded properly, by opening another terminal and executing: + ``` + ros2 control list_hardware_interfaces + ``` + You should get: + ``` + command interfaces + joint1/position [claimed] + joint2/position [claimed] + state interfaces + joint1/position + joint2/position + + ``` + Marker `[claimed]` by command interfaces means that a controller has access to command *RRBot*. + +1. Check is controllers are running: + ``` + ros2 control list_controllers + ``` + You should get: + ``` + joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active + forward_position_controller[forward_command_controller/ForwardCommandController] active + ``` + +1. If you get output from above you can send commands to *Forward Command Controller*, either: + + a. Manually using ros2 cli interface: + ``` + ros2 topic pub /position_commands std_msgs/msg/Float64MultiArray "data: + - 0.5 + - 0.5" + ``` + B. Or you can start a demo node which sends two goals every 5 seconds in a loop: + ``` + ros2 launch ros2_control_demo_bringup test_forward_position_controller.launch.py + ``` + You should now see orange and yellow blocks moving in `RViz`. + Also, you should see changing states in the terminal where launch file is started. + + +Files used for this demos: + - Launch file: [rrbot.launch.py](ros2_control_demo_bringup/launch/rrbot.launch.py) + - Controllers yaml: [rrbot_controllers.yaml](ros2_control_demo_bringup/config/rrbot_controllers.yaml) + - URDF file: [rrbot.urdf.xacro](ros2_control_demo_description/rrbot_description/urdf/rrbot.urdf.xacro) + - Description: [rrbot_description.urdf.xacro](ros2_control_demo_description/rrbot_description/urdf/rrbot_description.urdf.xacro) + - `ros2_control` tag: [rrbot.ros2_control.xacro](ros2_control_demo_description/rrbot_description/ros2_control/rrbot.ros2_control.xacro) + - RViz configuration: [rrbot.rviz](ros2_control_demo_description/rrbot_description/config/rrbot.rviz) + + - Hardware interface plugin: [rrbot_system_position_only.cpp](ros2_control_demo_hardware/src/rrbot_system_position_only.cpp) + + +Controllers from this demo: + - `Joint State Broadcaster` ([`ros2_controllers` repository](https://github.com/ros-controls/ros2_controllers)): [doc](https://ros-controls.github.io/control.ros.org/ros2_controllers/joint_state_broadcaster/doc/userdoc.html) + - `Forward Command Controller` ([`ros2_controllers` repository](https://github.com/ros-controls/ros2_controllers)): [doc](https://ros-controls.github.io/control.ros.org/ros2_controllers/forward_command_controller/doc/userdoc.html) diff --git a/ros2_control_demo_bringup/config/rrbot_controllers.yaml b/example_1/bringup/config/rrbot_controllers.yaml similarity index 100% rename from ros2_control_demo_bringup/config/rrbot_controllers.yaml rename to example_1/bringup/config/rrbot_controllers.yaml diff --git a/ros2_control_demo_bringup/launch/rrbot.launch.py b/example_1/bringup/launch/rrbot.launch.py similarity index 100% rename from ros2_control_demo_bringup/launch/rrbot.launch.py rename to example_1/bringup/launch/rrbot.launch.py diff --git a/ros2_control_demo_description/rrbot_description/ros2_control/rrbot.ros2_control.xacro b/example_1/description/rrbot.ros2_control.xacro similarity index 100% rename from ros2_control_demo_description/rrbot_description/ros2_control/rrbot.ros2_control.xacro rename to example_1/description/rrbot.ros2_control.xacro diff --git a/ros2_control_demo_description/rrbot_description/urdf/rrbot.urdf.xacro b/example_1/description/rrbot.urdf.xacro similarity index 100% rename from ros2_control_demo_description/rrbot_description/urdf/rrbot.urdf.xacro rename to example_1/description/rrbot.urdf.xacro diff --git a/ros2_control_demo_description/rrbot_description/urdf/rrbot_description.urdf.xacro b/example_1/description/rrbot_description.urdf.xacro similarity index 100% rename from ros2_control_demo_description/rrbot_description/urdf/rrbot_description.urdf.xacro rename to example_1/description/rrbot_description.urdf.xacro diff --git a/ros2_control_demo_hardware/src/rrbot_system_position_only.cpp b/example_1/hardware/rrbot.cpp similarity index 99% rename from ros2_control_demo_hardware/src/rrbot_system_position_only.cpp rename to example_1/hardware/rrbot.cpp index 1871e3292..06576229d 100644 --- a/ros2_control_demo_hardware/src/rrbot_system_position_only.cpp +++ b/example_1/hardware/rrbot.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ros2_control_demo_hardware/rrbot_system_position_only.hpp" +#include "ros2_control_demos_example_1/hardware/rrbot.hpp" #include #include diff --git a/ros2_control_demo_hardware/include/ros2_control_demo_hardware/rrbot_system_position_only.hpp b/example_1/hardware/rrbot.hpp similarity index 100% rename from ros2_control_demo_hardware/include/ros2_control_demo_hardware/rrbot_system_position_only.hpp rename to example_1/hardware/rrbot.hpp diff --git a/example_1/package.xml b/example_1/package.xml new file mode 100644 index 000000000..866c80bab --- /dev/null +++ b/example_1/package.xml @@ -0,0 +1,24 @@ + + + + ros2_control_demo_hardware + 0.0.0 + Demo package of `ros2_control` Hardware. This package provides example on how to define hardware of your own robot for ROS2 control. The package is used with `ros2_control_demo_bringup` from package `rrbot_description` and `diffbot_description`. + + Denis Štogl + + Apache-2.0 + + ament_cmake + + hardware_interface + pluginlib + rclcpp + rclcpp_lifecycle + + ament_cmake_gtest + + + ament_cmake + + diff --git a/ros2_control_test_nodes/package.xml b/ros2_control_test_nodes/package.xml deleted file mode 100644 index deac1d943..000000000 --- a/ros2_control_test_nodes/package.xml +++ /dev/null @@ -1,21 +0,0 @@ - - - - ros2_control_test_nodes - 0.0.0 - Demo nodes for showing and testing functionalities of the ros2_control framework. - - Denis Štogl - - Apache-2.0 - - rclpy - std_msgs - trajectory_msgs - - python3-pytest - - - ament_python - - diff --git a/ros2_control_test_nodes/resource/ros2_control_test_nodes b/ros2_control_test_nodes/resource/ros2_control_test_nodes deleted file mode 100644 index e69de29bb..000000000 diff --git a/ros2_control_test_nodes/ros2_control_test_nodes/__init__.py b/ros2_control_test_nodes/ros2_control_test_nodes/__init__.py deleted file mode 100644 index f37d75e96..000000000 --- a/ros2_control_test_nodes/ros2_control_test_nodes/__init__.py +++ /dev/null @@ -1,13 +0,0 @@ -# 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. diff --git a/ros2_control_test_nodes/ros2_control_test_nodes/publisher_joint_trajectory_controller.py b/ros2_control_test_nodes/ros2_control_test_nodes/publisher_joint_trajectory_controller.py deleted file mode 100644 index 11ca714d4..000000000 --- a/ros2_control_test_nodes/ros2_control_test_nodes/publisher_joint_trajectory_controller.py +++ /dev/null @@ -1,149 +0,0 @@ -# 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. - -import rclpy -from rclpy.node import Node -from builtin_interfaces.msg import Duration - -from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint -from sensor_msgs.msg import JointState - - -class PublisherJointTrajectory(Node): - def __init__(self): - super().__init__("publisher_position_trajectory_controller") - # Declare all parameters - self.declare_parameter("controller_name", "position_trajectory_controller") - self.declare_parameter("wait_sec_between_publish", 6) - self.declare_parameter("goal_names", ["pos1", "pos2"]) - self.declare_parameter("joints") - self.declare_parameter("check_starting_point", False) - self.declare_parameter("starting_point_limits") - - # Read parameters - controller_name = self.get_parameter("controller_name").value - wait_sec_between_publish = self.get_parameter("wait_sec_between_publish").value - goal_names = self.get_parameter("goal_names").value - self.joints = self.get_parameter("joints").value - self.check_starting_point = self.get_parameter("check_starting_point").value - self.starting_point = {} - - if self.joints is None or len(self.joints) == 0: - raise Exception('"joints" parameter is not set!') - - # starting point stuff - if self.check_starting_point: - # declare nested params - for name in self.joints: - param_name_tmp = "starting_point_limits" + "." + name - self.declare_parameter(param_name_tmp, [-2 * 3.14159, 2 * 3.14159]) - self.starting_point[name] = self.get_parameter(param_name_tmp).value - - for name in self.joints: - if len(self.starting_point[name]) != 2: - raise Exception('"starting_point" parameter is not set correctly!') - self.joint_state_sub = self.create_subscription( - JointState, "joint_states", self.joint_state_callback, 10 - ) - # initialize starting point status - if not self.check_starting_point: - self.starting_point_ok = True - else: - self.starting_point_ok = False - - self.joint_state_msg_received = False - - # Read all positions from parameters - self.goals = [] - for name in goal_names: - self.declare_parameter(name) - goal = self.get_parameter(name).value - if goal is None or len(goal) == 0: - raise Exception(f'Values for goal "{name}" not set!') - - float_goal = [] - for value in goal: - float_goal.append(float(value)) - self.goals.append(float_goal) - - publish_topic = "/" + controller_name + "/" + "joint_trajectory" - - self.get_logger().info( - 'Publishing {} goals on topic "{}" every {} s'.format( - len(goal_names), publish_topic, wait_sec_between_publish - ) - ) - - self.publisher_ = self.create_publisher(JointTrajectory, publish_topic, 1) - self.timer = self.create_timer(wait_sec_between_publish, self.timer_callback) - self.i = 0 - - def timer_callback(self): - - if self.starting_point_ok: - - traj = JointTrajectory() - traj.joint_names = self.joints - point = JointTrajectoryPoint() - point.positions = self.goals[self.i] - point.time_from_start = Duration(sec=4) - - traj.points.append(point) - self.publisher_.publish(traj) - - self.i += 1 - self.i %= len(self.goals) - - elif self.check_starting_point and not self.joint_state_msg_received: - self.get_logger().warn( - 'Start configuration could not be checked! Check "joint_state" topic!' - ) - else: - self.get_logger().warn("Start configuration is not within configured limits!") - - def joint_state_callback(self, msg): - - if not self.joint_state_msg_received: - - # check start state - limit_exceeded = [False] * len(msg.name) - for idx, enum in enumerate(msg.name): - if (msg.position[idx] < self.starting_point[enum][0]) or ( - msg.position[idx] > self.starting_point[enum][1] - ): - self.get_logger().warn(f"Starting point limits exceeded for joint {enum} !") - limit_exceeded[idx] = True - - if any(limit_exceeded): - self.starting_point_ok = False - else: - self.starting_point_ok = True - - self.joint_state_msg_received = True - else: - return - - -def main(args=None): - rclpy.init(args=args) - - publisher_joint_trajectory = PublisherJointTrajectory() - - rclpy.spin(publisher_joint_trajectory) - publisher_joint_trajectory.destroy_node() - rclpy.shutdown() - - -if __name__ == "__main__": - main() diff --git a/ros2_control_test_nodes/setup.cfg b/ros2_control_test_nodes/setup.cfg deleted file mode 100644 index 00e215cc1..000000000 --- a/ros2_control_test_nodes/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script-dir=$base/lib/ros2_control_test_nodes -[install] -install-scripts=$base/lib/ros2_control_test_nodes diff --git a/ros2_control_test_nodes/setup.py b/ros2_control_test_nodes/setup.py deleted file mode 100644 index 98f47ba19..000000000 --- a/ros2_control_test_nodes/setup.py +++ /dev/null @@ -1,57 +0,0 @@ -# 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 glob import glob - -from setuptools import setup - -package_name = "ros2_control_test_nodes" - -setup( - name=package_name, - version="0.0.1", - packages=[package_name], - data_files=[ - ("share/ament_index/resource_index/packages", ["resource/" + package_name]), - ("share/" + package_name, ["package.xml"]), - ("share/" + package_name, glob("launch/*.launch.py")), - ("share/" + package_name + "/configs", glob("configs/*.*")), - ], - install_requires=["setuptools"], - zip_safe=True, - author="Denis Štogl", - author_email="denis@stogl.de", - maintainer="Denis Štogl", - maintainer_email="denis@stogl.de", - keywords=["ROS"], - classifiers=[ - "Intended Audience :: Developers", - "License :: OSI Approved :: Apache Software License", - "Programming Language :: Python", - "Topic :: Software Development", - ], - description="Demo nodes for showing and testing functionalities of ros2_control framework.", - long_description="""\ -Demo nodes for showing and testing functionalities of the ros2_control framework.""", - license="Apache License, Version 2.0", - tests_require=["pytest"], - entry_points={ - "console_scripts": [ - "publisher_forward_position_controller = \ - ros2_control_test_nodes.publisher_forward_position_controller:main", - "publisher_joint_trajectory_controller = \ - ros2_control_test_nodes.publisher_joint_trajectory_controller:main", - ], - }, -)