diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml
index 069bf6ad..97dc9f8f 100644
--- a/.github/workflows/ci.yaml
+++ b/.github/workflows/ci.yaml
@@ -1,4 +1,4 @@
-name: Ignition ros2 control CI
+name: Gazebo-Sim ros2 control CI
on:
pull_request:
@@ -8,45 +8,77 @@ jobs:
runs-on: ubuntu-latest
strategy:
matrix:
- version: [fortress]
+ include:
+ - docker-image: "ubuntu:22.04"
+ gz-version: "fortress"
+ ros-distro: "humble"
+ - docker-image: "ubuntu:22.04"
+ gz-version: "fortress"
+ ros-distro: "rolling"
+ - docker-image: "ubuntu:22.04"
+ gz-version: "garden"
+ ros-distro: "humble"
+ - docker-image: "ubuntu:22.04"
+ gz-version: "garden"
+ ros-distro: "rolling"
env:
- IGNITION_VERSION: ${{ matrix.version }}
+ DOCKER_IMAGE: ${{ matrix.docker-image }}
+ GZ_VERSION: ${{ matrix.gz-version }}
+ ROS_DISTRO: ${{ matrix.ros-distro }}
container:
- image: ubuntu:22.04
+ image: ${{ matrix.docker-image }}
steps:
- uses: actions/checkout@v2
- name: Setup colcon workspace
id: configure
+ shell: bash
run: |
export DEBIAN_FRONTEND=noninteractive
apt update -qq
- apt install -qq -y lsb-release wget curl gnupg2
+ apt install -qq -y lsb-release wget curl gnupg2 git
cd ..
mkdir -p /home/ros2_ws/src
+ if [ "$ROS_DISTRO" == "rolling" ]; then
+ git clone https://github.com/gazebosim/ros_gz/
+ fi
+ if [ "$ROS_DISTRO" == "humble" ]; then
+ git clone https://github.com/gazebosim/ros_gz/ -b humble
+ fi
cp -r gz_ros2_control /home/ros2_ws/src/
- sh -c 'echo "deb http://packages.ros.org/ros2-testing/ubuntu `lsb_release -cs` main" > /etc/apt/sources.list.d/ros2-testing.list'
- curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | apt-key add -
+ curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
+ echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | tee /etc/apt/sources.list.d/ros2.list > /dev/null
+ wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg
+ echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null
+ if [ "$GZ_VERSION" == "garden" ]; then
+ export GZ_DEPS="libgz-sim7-dev libgz-plugin2-dev"
+ fi
+
apt-get update && apt-get upgrade -q -y
apt-get update && apt-get install -qq -y \
dirmngr \
python3-colcon-ros \
python3-colcon-common-extensions \
python3-rosdep \
- build-essential
+ build-essential \
+ ${GZ_DEPS}
+
+ if [ "$GZ_VERSION" == "garden" ]; then
+ export ROSDEP_ARGS="--skip-keys ros_gz_sim --skip-keys gz-plugin2 --skip-keys gz-sim7 --skip-keys gz-transport12 --skip-keys gz-math7 --skip-keys gz-msgs9"
+ fi
cd /home/ros2_ws/src/
rosdep init
rosdep update
- rosdep install --from-paths ./ -i -y --rosdistro humble --ignore-src
+ rosdep install --from-paths ./ -i -y --rosdistro ${ROS_DISTRO} --ignore-src ${ROSDEP_ARGS}
- name: Build project
id: build
run: |
cd /home/ros2_ws/
- . /opt/ros/humble/local_setup.sh
- colcon build --packages-up-to ign_ros2_control_demos
+ . /opt/ros/${ROS_DISTRO}/local_setup.sh
+ colcon build --packages-up-to gz_ros2_control_demos
- name: Run tests
id: test
run: |
cd /home/ros2_ws/
- . /opt/ros/humble/local_setup.sh
- colcon test --event-handlers console_direct+ --packages-select ign_ros2_control ign_ros2_control_demos
+ . /opt/ros/${ROS_DISTRO}/local_setup.sh
+ colcon test --event-handlers console_direct+ --packages-select gz_ros2_control gz_ros2_control_demos
colcon test-result
diff --git a/Dockerfile/Dockerfile b/Dockerfile/Dockerfile
index 349d0840..6b14d33f 100644
--- a/Dockerfile/Dockerfile
+++ b/Dockerfile/Dockerfile
@@ -1,7 +1,12 @@
FROM ubuntu:20.04
ENV DEBIAN_FRONTEND noninteractive
+<<<<<<< HEAD
ENV IGNITION_VERSION fortress
+=======
+ENV GZ_VERSION fortress
+ENV ROS_DISTRO rolling
+>>>>>>> ab810e7 (Renamed ign to gz (#67))
# Make sure everything is up to date before building from source
RUN apt-get update \
@@ -39,4 +44,4 @@ RUN cd /home/ros2_ws/ \
COPY entrypoint.sh /entrypoint.sh
ENTRYPOINT ["/entrypoint.sh"]
-CMD ros2 launch ign_ros2_control_demos cart_example_position.launch.py
+CMD ros2 launch gz_ros2_control_demos cart_example_position.launch.py
diff --git a/README.md b/README.md
index 28f5b990..b6009f89 100644
--- a/README.md
+++ b/README.md
@@ -1,9 +1,16 @@
-# ign_ros2_control
+# gz_ros2_control
+<<<<<<< HEAD
+=======
+ROS2 Distro | Build Status | Package build |
+:---------: | :----: | :----------: |
+[![Licence](https://img.shields.io/badge/License-Apache%202.0-blue.svg)](https://opensource.org/licenses/Apache-2.0) | [![Build Status](http://build.ros2.org/buildStatus/icon?job=Hdev__ign_ros2_control__ubuntu_focal_amd64)](http://build.ros2.org/job/Hdev__ign_ros2_control__ubuntu_focal_amd64) | [![Build Status](http://build.ros2.org/buildStatus/icon?job=Hbin_uF64__ign_ros2_control__ubuntu_focal_amd64__binary)](http://build.ros2.org/job/Hbin_uF64__ign_ros2_control__ubuntu_focal_amd64__binary) |
+
+>>>>>>> ab810e7 (Renamed ign to gz (#67))
This is a ROS 2 package for integrating the `ros2_control` controller architecture with the [Ignition Gazebo](http://ignitionrobotics.org/) simulator.
More information about `ros2_control` can be found here: https://control.ros.org/
-This package provides an Ignition Gazebo system plugin which instantiates a `ros2_control` controller manager and connects it to a Gazebo model.
+This package provides a Gazebo-Sim system plugin which instantiates a `ros2_control` controller manager and connects it to a Gazebo model.
Tested on:
@@ -17,12 +24,11 @@ If you want to run this with `ROS 2 Foxy` please check the branch `foxy`.
# Compile from source
-If you want compile this from source, you should choose the Ignition version. The default one is `citadel`:
+If you want compile this from source, you should choose the Gazebo version. The default one is `garden`:
```bash
-export IGNITION_VERSION=citadel
-export IGNITION_VERSION=edifice
-export IGNITION_VERSION=fortress
+export GZ_VERSION=fortress
+export GZ_VERSION=garden
```
Then create a workspace, clone the repo and compile it:
@@ -40,7 +46,7 @@ colcon build
## Video + Pictures
-![](img/ign_ros2_control.gif)
+![](img/gz_ros2_control.gif)
![](img/diff_drive.gif)
@@ -51,7 +57,7 @@ colcon build
```bash
cd Dockerfile
-docker build -t ign_ros2_control .
+docker build -t gz_ros2_control .
```
### To run the demo
@@ -61,7 +67,7 @@ docker build -t ign_ros2_control .
Docker allows us to run the demo without the GUI if configured properly. The following command runs the demo without the GUI:
```bash
-docker run -it --rm --name ignition_ros2_control_demo --net host ign_ros2_control ros2 launch ign_ros2_control_demos cart_example_position.launch.py gui:=false
+docker run -it --rm --name gz_ros2_control_demo --net host gz_ros2_control ros2 launch gz_ros2_control_demos cart_example_position.launch.py gui:=false
```
Then on your local machine, you can run the Gazebo client:
@@ -76,18 +82,18 @@ To run the demo with the GUI, we are going to use [rocker](https://github.com/os
images with customized local support injected for things like nvidia support. Rocker also supports user id specific files for cleaner
mounting file permissions. You can install this tool with the following [instructions](https://github.com/osrf/rocker/#installation) (make sure you meet all of the [prerequisites](https://github.com/osrf/rocker/#prerequisites)).
-The following command will launch Ignition:
+The following command will launch Gazebo:
```bash
-rocker --x11 --nvidia --name ignition_ros2_control_demo ign_ros2_control:latest
+rocker --x11 --nvidia --name gz_ros2_control_demo gz_ros2_control:latest
```
The following commands allow the cart to be moved along the rail:
```bash
-docker exec -it ignition_ros2_control_demo bash
+docker exec -it gz_ros2_control_demo bash
source /home/ros2_ws/install/setup.bash
-ros2 run ign_ros2_control_demos example_position
+ros2 run gz_ros2_control_demos example_position
```
## Add ros2_control tag to a URDF
@@ -100,9 +106,9 @@ include:
- `` tag including the robot controllers: commands and states.
```xml
-
+
- ign_ros2_control/IgnitionSystem
+ gz_ros2_control/GazeboSimSystem
@@ -118,31 +124,71 @@ include:
```
+<<<<<<< HEAD
## Add the ign_ros2_control plugin
+=======
+
+### Using mimic joints in simulation
+
+To use `mimic` joints in `gz_ros2_control` you should define its parameters to your URDF.
+We should include:
+
+- `` tag to the mimicked joint ([detailed manual(https://wiki.ros.org/urdf/XML/joint))
+- `mimic` and `multiplier` parameters to joint definition in `` tag
+
+```xml
+
+
+
+
+
+
+
+
+```
+
+```xml
+
+ right_finger_joint
+ 1
+
+
+
+
+
+```
+
+
+## Add the gz_ros2_control plugin
+>>>>>>> ab810e7 (Renamed ign to gz (#67))
In addition to the `ros2_control` tags, a Gazebo plugin needs to be added to your URDF that
actually parses the `ros2_control` tags and loads the appropriate hardware interfaces and
-controller manager. By default the `ign_ros2_control` plugin is very simple, though it is also
+controller manager. By default the `gz_ros2_control` plugin is very simple, though it is also
extensible via an additional plugin architecture to allow power users to create their own custom
robot hardware interfaces between `ros2_control` and Gazebo.
```xml
+<<<<<<< HEAD
+=======
+
+>>>>>>> ab810e7 (Renamed ign to gz (#67))
robot_descriptionrobot_state_publisher
- $(find ign_ros2_control_demos)/config/cartpole_controller.yaml
+ $(find gz_ros2_control_demos)/config/cartpole_controller.yaml
```
-The `ign_ros2_control` `` tag also has the following optional child elements:
+The `gz_ros2_control` `` tag also has the following optional child elements:
- ``: YAML file with the configuration of the controllers
-#### Default ign_ros2_control Behavior
+#### Default gz_ros2_control Behavior
-By default, without a `` tag, `ign_ros2_control` will attempt to get all of the information it needs to interface with a ros2_control-based controller out of the URDF. This is sufficient for most cases, and good for at least getting started.
+By default, without a `` tag, `gz_ros2_control` will attempt to get all of the information it needs to interface with a ros2_control-based controller out of the URDF. This is sufficient for most cases, and good for at least getting started.
The default behavior provides the following ros2_control interfaces:
@@ -150,24 +196,28 @@ The default behavior provides the following ros2_control interfaces:
- hardware_interface::EffortJointInterface
- hardware_interface::VelocityJointInterface
-#### Advanced: custom ign_ros2_control Simulation Plugins
+#### Advanced: custom gz_ros2_control Simulation Plugins
-The `ign_ros2_control` Gazebo plugin also provides a pluginlib-based interface to implement custom interfaces between Gazebo and `ros2_control` for simulating more complex mechanisms (nonlinear springs, linkages, etc).
+The `gz_ros2_control` Gazebo plugin also provides a pluginlib-based interface to implement custom interfaces between Gazebo and `ros2_control` for simulating more complex mechanisms (nonlinear springs, linkages, etc).
-These plugins must inherit the `ign_ros2_control::IgnitionSystemInterface`, which implements a simulated `ros2_control`
+These plugins must inherit the `gz_ros2_control::GazeboSimSystemInterface`, which implements a simulated `ros2_control`
`hardware_interface::SystemInterface`. SystemInterface provides API-level access to read and command joint properties.
-The respective IgnitionSystemInterface sub-class is specified in a URDF model and is loaded when the
+The respective GazeboSimSystemInterface sub-class is specified in a URDF model and is loaded when the
robot model is loaded. For example, the following XML will load the default plugin:
```xml
-
+
- ign_ros2_control/IgnitionSystem
+ gz_ros2_control/GazeboSimSystem
...
+<<<<<<< HEAD
+=======
+
+>>>>>>> ab810e7 (Renamed ign to gz (#67))
...
@@ -180,8 +230,13 @@ and use the tag `` to set the controller ma
```xml
+<<<<<<< HEAD
$(find ign_ros2_control_demos)/config/cartpole_controller.yaml
+=======
+
+ $(find gz_ros2_control_demos)/config/cartpole_controller.yaml
+>>>>>>> ab810e7 (Renamed ign to gz (#67))
controller_manager
@@ -210,16 +265,16 @@ cart_pole_controller:
```
#### Executing the examples
-There are some examples in the `ign_ros2_control_demos` package. These examples allow to launch a cart in a 30 meter rail.
+There are some examples in the `gz_ros2_control_demos` package. These examples allow to launch a cart in a 30 meter rail.
You can run some of the example configurations by running the following commands:
```bash
-ros2 launch ign_ros2_control_demos cart_example_position.launch.py
-ros2 launch ign_ros2_control_demos cart_example_velocity.launch.py
-ros2 launch ign_ros2_control_demos cart_example_effort.launch.py
-ros2 launch ign_ros2_control_demos diff_drive_example.launch.py
-ros2 launch ign_ros2_control_demos tricycle_drive_example.launch.py
+ros2 launch gz_ros2_control_demos cart_example_position.launch.py
+ros2 launch gz_ros2_control_demos cart_example_velocity.launch.py
+ros2 launch gz_ros2_control_demos cart_example_effort.launch.py
+ros2 launch gz_ros2_control_demos diff_drive_example.launch.py
+ros2 launch gz_ros2_control_demos tricycle_drive_example.launch.py
```
Send example commands:
@@ -227,9 +282,27 @@ Send example commands:
When the Gazebo world is launched, you can run some of the following commands to move the cart.
```bash
-ros2 run ign_ros2_control_demos example_position
-ros2 run ign_ros2_control_demos example_velocity
-ros2 run ign_ros2_control_demos example_effort
-ros2 run ign_ros2_control_demos example_diff_drive
-ros2 run ign_ros2_control_demos example_tricycle_drive
+ros2 run gz_ros2_control_demos example_position
+ros2 run gz_ros2_control_demos example_velocity
+ros2 run gz_ros2_control_demos example_effort
+ros2 run gz_ros2_control_demos example_diff_drive
+ros2 run gz_ros2_control_demos example_tricycle_drive
+```
+<<<<<<< HEAD
+=======
+
+The following example shows parallel gripper with mimic joint:
+
+![](img/gripper.gif)
+
+
+```bash
+ros2 launch gz_ros2_control_demos gripper_mimic_joint_example.launch.py
+```
+
+Send example commands:
+
+```bash
+ros2 run gz_ros2_control_demos example_gripper
```
+>>>>>>> ab810e7 (Renamed ign to gz (#67))
diff --git a/ign_ros2_control/CHANGELOG.rst b/gz_ros2_control/CHANGELOG.rst
similarity index 100%
rename from ign_ros2_control/CHANGELOG.rst
rename to gz_ros2_control/CHANGELOG.rst
diff --git a/ign_ros2_control/CMakeLists.txt b/gz_ros2_control/CMakeLists.txt
similarity index 52%
rename from ign_ros2_control/CMakeLists.txt
rename to gz_ros2_control/CMakeLists.txt
index f11c290f..5439c686 100644
--- a/ign_ros2_control/CMakeLists.txt
+++ b/gz_ros2_control/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.5)
-project(ign_ros2_control)
+project(gz_ros2_control)
# Default to C11
if(NOT CMAKE_C_STANDARD)
@@ -24,39 +24,41 @@ find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
-if("$ENV{IGNITION_VERSION}" STREQUAL "citadel")
- find_package(ignition-gazebo3 REQUIRED)
- set(IGN_GAZEBO_VER ${ignition-gazebo3_VERSION_MAJOR})
- message(STATUS "Compiling against Ignition Citadel")
+set(GZ_PLUGIN)
+set(GZ_SIM)
-elseif("$ENV{IGNITION_VERSION}" STREQUAL "edifice")
- find_package(ignition-gazebo5 REQUIRED)
- set(IGN_GAZEBO_VER ${ignition-gazebo5_VERSION_MAJOR})
- message(STATUS "Compiling against Ignition Edifice")
-
-elseif("$ENV{IGNITION_VERSION}" STREQUAL "fortress")
+if("$ENV{GZ_VERSION}" STREQUAL "fortress")
find_package(ignition-gazebo6 REQUIRED)
- set(IGN_GAZEBO_VER ${ignition-gazebo6_VERSION_MAJOR})
- message(STATUS "Compiling against Ignition Fortress")
-
+ set(GZ_SIM_VER ${ignition-gazebo6_VERSION_MAJOR})
+ message(STATUS "Compiling against Gazebo Fortress")
+ find_package(ignition-plugin1 REQUIRED)
+ set(GZ_PLUGIN_VER ${ignition-plugin1_VERSION_MAJOR})
+ set(GZ_PLUGIN ignition-plugin${GZ_PLUGIN_VER}::register)
+ set(GZ_SIM ignition-gazebo${GZ_SIM_VER}::core)
else()
- find_package(ignition-gazebo6 REQUIRED)
- set(IGN_GAZEBO_VER ${ignition-gazebo6_VERSION_MAJOR})
- message(STATUS "Compiling against Ignition Fortress")
+ find_package(gz-sim7 REQUIRED)
+ set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR})
+ message(STATUS "Compiling against Gazebo Garden")
+ find_package(gz-plugin2 REQUIRED)
+ set(GZ_PLUGIN_VER ${gz-plugin2_VERSION_MAJOR})
+ set(GZ_PLUGIN gz-plugin${GZ_PLUGIN_VER}::register)
+ set(GZ_SIM gz-sim${GZ_SIM_VER}::core)
+ add_definitions(-DGZ_HEADERS)
endif()
-find_package(ignition-plugin1 REQUIRED)
-set(IGN_PLUGIN_VER ${ignition-plugin1_VERSION_MAJOR})
+if("$ENV{ROS_DISTRO}" STREQUAL "rolling")
+ add_definitions(-DROLLING)
+endif()
include_directories(include)
add_library(${PROJECT_NAME}-system SHARED
- src/ign_ros2_control_plugin.cpp
+ src/gz_ros2_control_plugin.cpp
)
target_link_libraries(${PROJECT_NAME}-system
- ignition-gazebo${IGN_GAZEBO_VER}::core
- ignition-plugin${IGN_PLUGIN_VER}::register
+ ${GZ_SIM}
+ ${GZ_PLUGIN}
)
ament_target_dependencies(${PROJECT_NAME}-system
ament_index_cpp
@@ -70,21 +72,21 @@ ament_target_dependencies(${PROJECT_NAME}-system
#########
-add_library(ign_hardware_plugins SHARED
- src/ign_system.cpp
+add_library(gz_hardware_plugins SHARED
+ src/gz_system.cpp
)
-ament_target_dependencies(ign_hardware_plugins
+ament_target_dependencies(gz_hardware_plugins
rclcpp_lifecycle
hardware_interface
rclcpp
)
-target_link_libraries(ign_hardware_plugins
- ignition-gazebo${IGN_GAZEBO_VER}::core
+target_link_libraries(gz_hardware_plugins
+ ${GZ_SIM}
)
## Install
install(TARGETS
- ign_hardware_plugins
+ gz_hardware_plugins
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
@@ -97,14 +99,14 @@ if(BUILD_TESTING)
endif()
ament_export_include_directories(include)
-ament_export_libraries(${PROJECT_NAME} ign_hardware_plugins)
+ament_export_libraries(${PROJECT_NAME} gz_hardware_plugins)
# Install directories
install(TARGETS ${PROJECT_NAME}-system
DESTINATION lib
)
-pluginlib_export_plugin_description_file(ign_ros2_control ign_hardware_plugins.xml)
+pluginlib_export_plugin_description_file(gz_ros2_control gz_hardware_plugins.xml)
# Setup the project
ament_package()
diff --git a/ign_ros2_control/LICENSE b/gz_ros2_control/LICENSE
similarity index 100%
rename from ign_ros2_control/LICENSE
rename to gz_ros2_control/LICENSE
diff --git a/gz_ros2_control/gz_hardware_plugins.xml b/gz_ros2_control/gz_hardware_plugins.xml
new file mode 100644
index 00000000..40ae92fe
--- /dev/null
+++ b/gz_ros2_control/gz_hardware_plugins.xml
@@ -0,0 +1,19 @@
+
+
+
+ GazeboPositionJoint
+
+
+
+
+ GazeboPositionJoint
+
+
+
+
diff --git a/gz_ros2_control/include/gz_ros2_control/gz_ros2_control_plugin.hpp b/gz_ros2_control/include/gz_ros2_control/gz_ros2_control_plugin.hpp
new file mode 100644
index 00000000..e7c26603
--- /dev/null
+++ b/gz_ros2_control/include/gz_ros2_control/gz_ros2_control_plugin.hpp
@@ -0,0 +1,68 @@
+// Copyright 2021 Open Source Robotics Foundation, Inc.
+//
+// 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 GZ_ROS2_CONTROL__GZ_ROS2_CONTROL_PLUGIN_HPP_
+#define GZ_ROS2_CONTROL__GZ_ROS2_CONTROL_PLUGIN_HPP_
+
+#include
+
+#ifdef GZ_HEADERS
+#include
+namespace sim = gz::sim;
+#else
+#include
+namespace sim = ignition::gazebo;
+#endif
+
+namespace gz_ros2_control
+{
+// Forward declarations.
+class GazeboSimROS2ControlPluginPrivate;
+
+class GazeboSimROS2ControlPlugin
+ : public sim::System,
+ public sim::ISystemConfigure,
+ public sim::ISystemPreUpdate,
+ public sim::ISystemPostUpdate
+{
+public:
+ /// \brief Constructor
+ GazeboSimROS2ControlPlugin();
+
+ /// \brief Destructor
+ ~GazeboSimROS2ControlPlugin() override;
+
+ // Documentation inherited
+ void Configure(
+ const sim::Entity & _entity,
+ const std::shared_ptr & _sdf,
+ sim::EntityComponentManager & _ecm,
+ sim::EventManager & _eventMgr) override;
+
+ // Documentation inherited
+ void PreUpdate(
+ const sim::UpdateInfo & _info,
+ sim::EntityComponentManager & _ecm) override;
+
+ void PostUpdate(
+ const sim::UpdateInfo & _info,
+ const sim::EntityComponentManager & _ecm) override;
+
+private:
+ /// \brief Private data pointer.
+ std::unique_ptr dataPtr;
+};
+} // namespace gz_ros2_control
+
+#endif // GZ_ROS2_CONTROL__GZ_ROS2_CONTROL_PLUGIN_HPP_
diff --git a/ign_ros2_control/include/ign_ros2_control/ign_system.hpp b/gz_ros2_control/include/gz_ros2_control/gz_system.hpp
similarity index 81%
rename from ign_ros2_control/include/ign_ros2_control/ign_system.hpp
rename to gz_ros2_control/include/gz_ros2_control/gz_system.hpp
index f766f3ec..8dc81f18 100644
--- a/ign_ros2_control/include/ign_ros2_control/ign_system.hpp
+++ b/gz_ros2_control/include/gz_ros2_control/gz_system.hpp
@@ -13,29 +13,29 @@
// limitations under the License.
-#ifndef IGN_ROS2_CONTROL__IGN_SYSTEM_HPP_
-#define IGN_ROS2_CONTROL__IGN_SYSTEM_HPP_
+#ifndef GZ_ROS2_CONTROL__GZ_SYSTEM_HPP_
+#define GZ_ROS2_CONTROL__GZ_SYSTEM_HPP_
#include
-
+
- ign_ros2_control/IgnitionSystem
+ gz_ros2_control/GazeboSimSystem
@@ -80,8 +80,8 @@
-
- $(find ign_ros2_control_demos)/config/cartpole_controller_effort.yaml
+
+ $(find gz_ros2_control_demos)/config/cartpole_controller_effort.yaml
diff --git a/ign_ros2_control_demos/urdf/test_cart_position.xacro.urdf b/gz_ros2_control_demos/urdf/test_cart_position.xacro.urdf
similarity index 79%
rename from ign_ros2_control_demos/urdf/test_cart_position.xacro.urdf
rename to gz_ros2_control_demos/urdf/test_cart_position.xacro.urdf
index eeff47ec..a7faaac7 100644
--- a/ign_ros2_control_demos/urdf/test_cart_position.xacro.urdf
+++ b/gz_ros2_control_demos/urdf/test_cart_position.xacro.urdf
@@ -12,6 +12,12 @@
+
+
+
+
+
+
@@ -24,6 +30,12 @@
+
+
+
+
+
+
@@ -43,9 +55,9 @@
-
+
- ign_ros2_control/IgnitionSystem
+ gz_ros2_control/GazeboSimSystem
@@ -53,7 +65,7 @@
15
- -5.0
+ 5.0
@@ -82,8 +94,8 @@
-
- $(find ign_ros2_control_demos)/config/cartpole_controller_position.yaml
+
+ $(find gz_ros2_control_demos)/config/cartpole_controller_position.yaml
diff --git a/ign_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf b/gz_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf
similarity index 89%
rename from ign_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf
rename to gz_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf
index 59a960a1..71b0c93f 100644
--- a/ign_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf
+++ b/gz_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf
@@ -4,6 +4,7 @@
+
@@ -66,7 +67,11 @@
-
+
+
+
+
+
@@ -111,9 +116,9 @@
-
+
- ign_ros2_control/IgnitionSystem
+ gz_ros2_control/GazeboSimSystem
@@ -160,11 +165,11 @@
-
- $(find ign_ros2_control_demos)/config/cartpole_controller_velocity.yaml
+
+ $(find gz_ros2_control_demos)/config/cartpole_controller_velocity.yaml
diff --git a/ign_ros2_control_demos/urdf/test_diff_drive.xacro.urdf b/gz_ros2_control_demos/urdf/test_diff_drive.xacro.urdf
similarity index 92%
rename from ign_ros2_control_demos/urdf/test_diff_drive.xacro.urdf
rename to gz_ros2_control_demos/urdf/test_diff_drive.xacro.urdf
index e608ed9e..7b77b090 100644
--- a/ign_ros2_control_demos/urdf/test_diff_drive.xacro.urdf
+++ b/gz_ros2_control_demos/urdf/test_diff_drive.xacro.urdf
@@ -132,9 +132,9 @@
-
+
- ign_ros2_control/IgnitionSystem
+ gz_ros2_control/GazeboSimSystem
@@ -156,8 +156,8 @@
-
- $(find ign_ros2_control_demos)/config/diff_drive_controller_velocity.yaml
+
+ $(find gz_ros2_control_demos)/config/diff_drive_controller_velocity.yaml
diff --git a/gz_ros2_control_demos/urdf/test_gripper_mimic_joint.xacro.urdf b/gz_ros2_control_demos/urdf/test_gripper_mimic_joint.xacro.urdf
new file mode 100644
index 00000000..555bd493
--- /dev/null
+++ b/gz_ros2_control_demos/urdf/test_gripper_mimic_joint.xacro.urdf
@@ -0,0 +1,105 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ gz_ros2_control/GazeboSimSystem
+
+
+
+
+ 0.15
+
+
+
+
+
+ right_finger_joint
+ 1
+
+
+
+
+
+
+
+
+
+ $(find gz_ros2_control_demos)/config/gripper_controller.yaml
+
+
+
diff --git a/ign_ros2_control_demos/urdf/test_tricycle_drive.xacro.urdf b/gz_ros2_control_demos/urdf/test_tricycle_drive.xacro.urdf
similarity index 93%
rename from ign_ros2_control_demos/urdf/test_tricycle_drive.xacro.urdf
rename to gz_ros2_control_demos/urdf/test_tricycle_drive.xacro.urdf
index 7d58323d..c0971c1a 100644
--- a/ign_ros2_control_demos/urdf/test_tricycle_drive.xacro.urdf
+++ b/gz_ros2_control_demos/urdf/test_tricycle_drive.xacro.urdf
@@ -150,9 +150,9 @@
-
+
- ign_ros2_control/IgnitionSystem
+ gz_ros2_control/GazeboSimSystem
@@ -167,8 +167,8 @@
-
- $(find ign_ros2_control_demos)/config/tricycle_drive_controller.yaml
+
+ $(find gz_ros2_control_demos)/config/tricycle_drive_controller.yaml
diff --git a/ign_ros2_control/ign_hardware_plugins.xml b/ign_ros2_control/ign_hardware_plugins.xml
deleted file mode 100644
index 3d245541..00000000
--- a/ign_ros2_control/ign_hardware_plugins.xml
+++ /dev/null
@@ -1,10 +0,0 @@
-
-
-
- GazeboPositionJoint
-
-
-
diff --git a/ign_ros2_control/include/ign_ros2_control/ign_ros2_control_plugin.hpp b/ign_ros2_control/include/ign_ros2_control/ign_ros2_control_plugin.hpp
deleted file mode 100644
index c7be9aef..00000000
--- a/ign_ros2_control/include/ign_ros2_control/ign_ros2_control_plugin.hpp
+++ /dev/null
@@ -1,62 +0,0 @@
-// Copyright 2021 Open Source Robotics Foundation, Inc.
-//
-// 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 IGN_ROS2_CONTROL__IGN_ROS2_CONTROL_PLUGIN_HPP_
-#define IGN_ROS2_CONTROL__IGN_ROS2_CONTROL_PLUGIN_HPP_
-
-#include
-
-#include
-
-namespace ign_ros2_control
-{
-// Forward declarations.
-class IgnitionROS2ControlPluginPrivate;
-
-class IgnitionROS2ControlPlugin
- : public ignition::gazebo::System,
- public ignition::gazebo::ISystemConfigure,
- public ignition::gazebo::ISystemPreUpdate,
- public ignition::gazebo::ISystemPostUpdate
-{
-public:
- /// \brief Constructor
- IgnitionROS2ControlPlugin();
-
- /// \brief Destructor
- ~IgnitionROS2ControlPlugin() override;
-
- // Documentation inherited
- void Configure(
- const ignition::gazebo::Entity & _entity,
- const std::shared_ptr & _sdf,
- ignition::gazebo::EntityComponentManager & _ecm,
- ignition::gazebo::EventManager & _eventMgr) override;
-
- // Documentation inherited
- void PreUpdate(
- const ignition::gazebo::UpdateInfo & _info,
- ignition::gazebo::EntityComponentManager & _ecm) override;
-
- void PostUpdate(
- const ignition::gazebo::UpdateInfo & _info,
- const ignition::gazebo::EntityComponentManager & _ecm) override;
-
-private:
- /// \brief Private data pointer.
- std::unique_ptr dataPtr;
-};
-} // namespace ign_ros2_control
-
-#endif // IGN_ROS2_CONTROL__IGN_ROS2_CONTROL_PLUGIN_HPP_
diff --git a/img/gz_ros2_control.gif b/img/gz_ros2_control.gif
new file mode 100644
index 00000000..65664bde
Binary files /dev/null and b/img/gz_ros2_control.gif differ