diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml
index e4e6e4eee31cd..b70b4fb24d892 100644
--- a/launch/tier4_system_launch/launch/system.launch.xml
+++ b/launch/tier4_system_launch/launch/system.launch.xml
@@ -22,6 +22,12 @@
+
+
+
+
+
+
@@ -62,7 +68,7 @@
-
+
@@ -76,7 +82,7 @@
-
+
@@ -99,6 +105,29 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/system/hazard_status_converter/launch/hazard_status_converter.launch.xml b/system/hazard_status_converter/launch/hazard_status_converter.launch.xml
index ff50dec3a342f..f3b07bfa94834 100644
--- a/system/hazard_status_converter/launch/hazard_status_converter.launch.xml
+++ b/system/hazard_status_converter/launch/hazard_status_converter.launch.xml
@@ -1,3 +1,6 @@
-
+
+
+
+
diff --git a/system/hazard_status_converter/src/converter.cpp b/system/hazard_status_converter/src/converter.cpp
index b09f3de891b45..e1da4f463f06d 100644
--- a/system/hazard_status_converter/src/converter.cpp
+++ b/system/hazard_status_converter/src/converter.cpp
@@ -127,9 +127,9 @@ namespace hazard_status_converter
Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", options)
{
- pub_hazard_ = create_publisher("/hazard_status", rclcpp::QoS(1));
+ pub_hazard_ = create_publisher("~/hazard_status", rclcpp::QoS(1));
sub_graph_ = create_subscription(
- "/diagnostics_graph", rclcpp::QoS(3),
+ "~/diagnostics_graph", rclcpp::QoS(3),
std::bind(&Converter::on_graph, this, std::placeholders::_1));
}