diff --git a/.github/workflows/ros2-ci.yml b/.github/workflows/ros2-ci.yml
index b95c0fae..7f3bf55e 100644
--- a/.github/workflows/ros2-ci.yml
+++ b/.github/workflows/ros2-ci.yml
@@ -9,9 +9,6 @@ jobs:
strategy:
matrix:
include:
- - docker-image: "ubuntu:20.04"
- ignition-version: "citadel"
- ros-distro: "galactic"
- docker-image: "ubuntu:20.04"
ignition-version: "edifice"
ros-distro: "galactic"
diff --git a/README.md b/README.md
index 2f4b147d..e162141a 100644
--- a/README.md
+++ b/README.md
@@ -9,7 +9,6 @@ Noetic | Edifice | [noetic](https://github.com/osrf/ros_ign/tree/noetic) | only
Noetic | Fortress | [noetic](https://github.com/osrf/ros_ign/tree/noetic) | only from source
Foxy | Citadel | [foxy](https://github.com/osrf/ros_ign/tree/foxy) | https://packages.ros.org
Foxy | Edifice | [foxy](https://github.com/osrf/ros_ign/tree/foxy) | only from source
-Galactic | Citadel | [galactic](https://github.com/osrf/ros_ign/tree/galactic) | only from source
Galactic | Edifice | [galactic](https://github.com/osrf/ros_ign/tree/galactic) | https://packages.ros.org
Galactic | Fortress | [galactic](https://github.com/osrf/ros_ign/tree/galactic) | only from source
Rolling | Edifice | [ros2](https://github.com/osrf/ros_ign/tree/ros2) | https://packages.ros.org
@@ -74,7 +73,7 @@ Be sure you've installed
#### Ignition
-Install either [Citadel, Edifice or Fortress](https://ignitionrobotics.org/docs).
+Install either [Edifice or Fortress](https://ignitionrobotics.org/docs).
Set the `IGNITION_VERSION` environment variable to the Ignition version you'd
like to compile against. For example:
diff --git a/ros_ign_bridge/CMakeLists.txt b/ros_ign_bridge/CMakeLists.txt
index 8fa89dd3..2e4da840 100644
--- a/ros_ign_bridge/CMakeLists.txt
+++ b/ros_ign_bridge/CMakeLists.txt
@@ -21,17 +21,8 @@ find_package(std_msgs REQUIRED)
find_package(tf2_msgs REQUIRED)
find_package(trajectory_msgs REQUIRED)
-# Citadel
-if("$ENV{IGNITION_VERSION}" STREQUAL "citadel")
- find_package(ignition-transport8 REQUIRED)
- set(IGN_TRANSPORT_VER ${ignition-transport8_VERSION_MAJOR})
-
- find_package(ignition-msgs5 REQUIRED)
- set(IGN_MSGS_VER ${ignition-msgs5_VERSION_MAJOR})
-
- message(STATUS "Compiling against Ignition Citadel")
# Fortress
-elseif("$ENV{IGNITION_VERSION}" STREQUAL "fortress")
+if("$ENV{IGNITION_VERSION}" STREQUAL "fortress")
find_package(ignition-transport11 REQUIRED)
set(IGN_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR})
diff --git a/ros_ign_bridge/package.xml b/ros_ign_bridge/package.xml
index ee9a933a..9b821a64 100644
--- a/ros_ign_bridge/package.xml
+++ b/ros_ign_bridge/package.xml
@@ -31,9 +31,6 @@
ignition-transport10
ignition-msgs7
ignition-transport10
-
- ignition-msgs5
- ignition-transport8
ament_cmake_gtest
ament_lint_auto
diff --git a/ros_ign_gazebo/CMakeLists.txt b/ros_ign_gazebo/CMakeLists.txt
index a7130638..1c3ae56a 100644
--- a/ros_ign_gazebo/CMakeLists.txt
+++ b/ros_ign_gazebo/CMakeLists.txt
@@ -14,17 +14,8 @@ find_package(ament_cmake REQUIRED)
find_package(ignition-math6 REQUIRED)
find_package(rclcpp REQUIRED)
-# Citadel
-if("$ENV{IGNITION_VERSION}" STREQUAL "citadel")
- find_package(ignition-transport8 REQUIRED)
- set(IGN_TRANSPORT_VER ${ignition-transport8_VERSION_MAJOR})
-
- find_package(ignition-msgs5 REQUIRED)
- set(IGN_MSGS_VER ${ignition-msgs5_VERSION_MAJOR})
-
- message(STATUS "Compiling against Ignition Citadel")
# Fortress
-elseif("$ENV{IGNITION_VERSION}" STREQUAL "fortress")
+if("$ENV{IGNITION_VERSION}" STREQUAL "fortress")
find_package(ignition-transport11 REQUIRED)
set(IGN_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR})
diff --git a/ros_ign_gazebo/package.xml b/ros_ign_gazebo/package.xml
index 8daf16a7..03842e98 100644
--- a/ros_ign_gazebo/package.xml
+++ b/ros_ign_gazebo/package.xml
@@ -22,8 +22,6 @@
ignition-gazebo5
ignition-gazebo5
-
- ignition-gazebo3
ament_lint_auto
ament_lint_common
diff --git a/ros_ign_gazebo_demos/package.xml b/ros_ign_gazebo_demos/package.xml
index 695b7e05..f0df07aa 100644
--- a/ros_ign_gazebo_demos/package.xml
+++ b/ros_ign_gazebo_demos/package.xml
@@ -12,8 +12,6 @@
ignition-gazebo5
ignition-gazebo5
-
- ignition-gazebo3
image_transport_plugins
robot_state_publisher
diff --git a/ros_ign_image/CMakeLists.txt b/ros_ign_image/CMakeLists.txt
index e6715be0..de3bb1a2 100644
--- a/ros_ign_image/CMakeLists.txt
+++ b/ros_ign_image/CMakeLists.txt
@@ -16,17 +16,8 @@ find_package(ros_ign_bridge REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
-# Citadel
-if("$ENV{IGNITION_VERSION}" STREQUAL "citadel")
- find_package(ignition-transport8 REQUIRED)
- set(IGN_TRANSPORT_VER ${ignition-transport8_VERSION_MAJOR})
-
- find_package(ignition-msgs5 REQUIRED)
- set(IGN_MSGS_VER ${ignition-msgs5_VERSION_MAJOR})
-
- message(STATUS "Compiling against Ignition Citadel")
# Fortress
-elseif("$ENV{IGNITION_VERSION}" STREQUAL "fortress")
+if("$ENV{IGNITION_VERSION}" STREQUAL "fortress")
find_package(ignition-transport11 REQUIRED)
set(IGN_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR})
diff --git a/ros_ign_image/package.xml b/ros_ign_image/package.xml
index 87974ca9..0227285b 100644
--- a/ros_ign_image/package.xml
+++ b/ros_ign_image/package.xml
@@ -21,9 +21,6 @@
ignition-transport10
ignition-msgs7
ignition-transport10
-
- ignition-msgs5
- ignition-transport8
ament_lint_auto
ament_lint_common