diff --git a/bitbots_localization/CMakeLists.txt b/bitbots_localization/CMakeLists.txt
index 1e558a0..4f38c37 100644
--- a/bitbots_localization/CMakeLists.txt
+++ b/bitbots_localization/CMakeLists.txt
@@ -104,5 +104,4 @@ install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(TARGETS localization DESTINATION lib/${PROJECT_NAME})
-
ament_package()
diff --git a/bitbots_localization_handler/bitbots_localization_handler/localization_dsd/decisions/game_state.py b/bitbots_localization_handler/bitbots_localization_handler/localization_dsd/decisions/game_state.py
index ca1d7d5..23b2f94 100644
--- a/bitbots_localization_handler/bitbots_localization_handler/localization_dsd/decisions/game_state.py
+++ b/bitbots_localization_handler/bitbots_localization_handler/localization_dsd/decisions/game_state.py
@@ -1,4 +1,4 @@
-from bitbots_msgs.msg import GameState
+from game_controller_hl_interfaces.msg import GameState
from bitbots_localization_handler.localization_dsd.decisions import AbstractLocalizationDecisionElement
diff --git a/bitbots_localization_handler/bitbots_localization_handler/localization_handler.py b/bitbots_localization_handler/bitbots_localization_handler/localization_handler.py
index 4ce846d..1978df5 100755
--- a/bitbots_localization_handler/bitbots_localization_handler/localization_handler.py
+++ b/bitbots_localization_handler/bitbots_localization_handler/localization_handler.py
@@ -3,8 +3,9 @@
import rclpy
from ament_index_python import get_package_share_directory
-from bitbots_msgs.msg import GameState, RobotControlState
+from bitbots_msgs.msg import RobotControlState
from dynamic_stack_decider.dsd import DSD
+from game_controller_hl_interfaces.msg import GameState
from geometry_msgs.msg import PoseWithCovarianceStamped
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup, ReentrantCallbackGroup
from rclpy.executors import MultiThreadedExecutor
diff --git a/bitbots_localization_handler/package.xml b/bitbots_localization_handler/package.xml
index 110c8ea..a860197 100644
--- a/bitbots_localization_handler/package.xml
+++ b/bitbots_localization_handler/package.xml
@@ -17,6 +17,7 @@
bitbots_msgs
bitbots_utils
dynamic_stack_decider
+ game_controller_hl_interfaces
geometry_msgs
python3-numpy
rclpy