diff --git a/aip_x1_launch/launch/pointcloud_preprocessor.launch.py b/aip_x1_launch/launch/pointcloud_preprocessor.launch.py
index bf120a8f..4a3ad9e1 100644
--- a/aip_x1_launch/launch/pointcloud_preprocessor.launch.py
+++ b/aip_x1_launch/launch/pointcloud_preprocessor.launch.py
@@ -37,7 +37,7 @@ def launch_setup(context, *args, **kwargs):
         parameters=[
             {
                 "input_topics": [
-                    "/sensing/lidar/top/outlier_filtered/pointcloud",
+                    "/sensing/lidar/top/pointcloud",
                     "/sensing/lidar/front_left/min_range_cropped/pointcloud",
                     "/sensing/lidar/front_right/min_range_cropped/pointcloud",
                     "/sensing/lidar/front_center/min_range_cropped/pointcloud",
diff --git a/aip_x1_launch/launch/topic_state_monitor.launch.py b/aip_x1_launch/launch/topic_state_monitor.launch.py
index 6692021d..b45b0f4e 100644
--- a/aip_x1_launch/launch/topic_state_monitor.launch.py
+++ b/aip_x1_launch/launch/topic_state_monitor.launch.py
@@ -81,7 +81,7 @@ def generate_launch_description():
         name="topic_state_monitor_top_outlier_filtered",
         parameters=[
             {
-                "topic": "/sensing/lidar/top/outlier_filtered/pointcloud",
+                "topic": "/sensing/lidar/top/pointcloud",
                 "topic_type": "sensor_msgs/msg/PointCloud2",
                 "best_effort": True,
                 "diag_name": "sensing_topic_status",
diff --git a/aip_x1_launch/launch/topic_state_monitor.launch.xml b/aip_x1_launch/launch/topic_state_monitor.launch.xml
index 6115d18e..8912fb67 100644
--- a/aip_x1_launch/launch/topic_state_monitor.launch.xml
+++ b/aip_x1_launch/launch/topic_state_monitor.launch.xml
@@ -34,7 +34,7 @@
   <!-- Topic Monitor for Concat Filter -->
   <include file="$(find-pkg-share topic_state_monitor)/launch/topic_state_monitor.launch.xml">
     <arg name="node_name_suffix" value="top_outlier_filtered"/>
-    <arg name="topic" value="/sensing/lidar/top/outlier_filtered/pointcloud"/>
+    <arg name="topic" value="/sensing/lidar/top/pointcloud"/>
     <arg name="topic_type" value="sensor_msgs/msg/PointCloud2"/>
     <arg name="best_effort" value="true"/>
     <arg name="diag_name" value="sensing_topic_status"/>
diff --git a/aip_x1_launch/launch/velodyne_node_container.launch.py b/aip_x1_launch/launch/velodyne_node_container.launch.py
index 95af023c..56b35116 100644
--- a/aip_x1_launch/launch/velodyne_node_container.launch.py
+++ b/aip_x1_launch/launch/velodyne_node_container.launch.py
@@ -128,7 +128,7 @@ def create_parameter_dict(*args):
             name="ring_outlier_filter",
             remappings=[
                 ("input", "rectified/pointcloud_ex"),
-                ("output", "outlier_filtered/pointcloud"),
+                ("output", "pointcloud"),
             ],
             extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
         )
diff --git a/aip_x2_launch/launch/pandar_node_container.launch.py b/aip_x2_launch/launch/pandar_node_container.launch.py
index 4c87d76c..cfb39cc4 100644
--- a/aip_x2_launch/launch/pandar_node_container.launch.py
+++ b/aip_x2_launch/launch/pandar_node_container.launch.py
@@ -208,7 +208,7 @@ def create_parameter_dict(*args):
         name="ring_outlier_filter",
         remappings=[
             ("input", "rectified/pointcloud_ex"),
-            ("output", "outlier_filtered/pointcloud"),
+            ("output", "pointcloud"),
         ],
         extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
     )
@@ -219,7 +219,7 @@ def create_parameter_dict(*args):
         name="dual_return_filter",
         remappings=[
             ("input", "rectified/pointcloud_ex"),
-            ("output", "outlier_filtered/pointcloud"),
+            ("output", "pointcloud"),
         ],
         parameters=[
             {
diff --git a/aip_x2_launch/launch/pointcloud_preprocessor.launch.py b/aip_x2_launch/launch/pointcloud_preprocessor.launch.py
index ae5c2022..4ef586ff 100644
--- a/aip_x2_launch/launch/pointcloud_preprocessor.launch.py
+++ b/aip_x2_launch/launch/pointcloud_preprocessor.launch.py
@@ -38,14 +38,14 @@ def launch_setup(context, *args, **kwargs):
         parameters=[
             {
                 "input_topics": [
-                    "/sensing/lidar/front_upper/outlier_filtered/pointcloud",
-                    "/sensing/lidar/front_lower/outlier_filtered/pointcloud",
-                    "/sensing/lidar/left_upper/outlier_filtered/pointcloud",
-                    "/sensing/lidar/left_lower/outlier_filtered/pointcloud",
-                    "/sensing/lidar/right_upper/outlier_filtered/pointcloud",
-                    "/sensing/lidar/right_lower/outlier_filtered/pointcloud",
-                    "/sensing/lidar/rear_upper/outlier_filtered/pointcloud",
-                    "/sensing/lidar/rear_lower/outlier_filtered/pointcloud",
+                    "/sensing/lidar/front_upper/pointcloud",
+                    "/sensing/lidar/front_lower/pointcloud",
+                    "/sensing/lidar/left_upper/pointcloud",
+                    "/sensing/lidar/left_lower/pointcloud",
+                    "/sensing/lidar/right_upper/pointcloud",
+                    "/sensing/lidar/right_lower/pointcloud",
+                    "/sensing/lidar/rear_upper/pointcloud",
+                    "/sensing/lidar/rear_lower/pointcloud",
                 ],
                 "input_offset": [0.025, 0.025, 0.01, 0.0, 0.05, 0.05, 0.05, 0.05],
                 "timeout_sec": 0.075,
diff --git a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
index 377c916e..e1888824 100644
--- a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
+++ b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
@@ -38,10 +38,10 @@ def launch_setup(context, *args, **kwargs):
         parameters=[
             {
                 "input_topics": [
-                    "/sensing/lidar/top/outlier_filtered/pointcloud",
-                    "/sensing/lidar/left/outlier_filtered/pointcloud",
-                    "/sensing/lidar/right/outlier_filtered/pointcloud",
-                    "/sensing/lidar/rear/outlier_filtered/pointcloud",
+                    "/sensing/lidar/top/pointcloud",
+                    "/sensing/lidar/left/pointcloud",
+                    "/sensing/lidar/right/pointcloud",
+                    "/sensing/lidar/rear/pointcloud",
                 ],
                 "output_frame": LaunchConfiguration("base_frame"),
                 "input_offset": [
diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py
index a237372e..a79681b8 100644
--- a/common_sensor_launch/launch/nebula_node_container.launch.py
+++ b/common_sensor_launch/launch/nebula_node_container.launch.py
@@ -187,7 +187,7 @@ def create_parameter_dict(*args):
             name="ring_outlier_filter",
             remappings=[
                 ("input", "rectified/pointcloud_ex"),
-                ("output", "outlier_filtered/pointcloud"),
+                ("output", "pointcloud"),
             ],
             extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
         )