From 9af729134148e616dd0c2b8e1d3a34c93ffebd67 Mon Sep 17 00:00:00 2001
From: Shintaro Sakoda <shintaro.sakoda@tier4.jp>
Date: Fri, 25 Oct 2024 09:39:27 +0900
Subject: [PATCH] Removed common_awsim_sensor_launch

Signed-off-by: Shintaro Sakoda <shintaro.sakoda@tier4.jp>
---
 .../launch/lidar.launch.xml                   |  6 +--
 common_awsim_sensor_launch/CMakeLists.txt     | 15 -------
 .../distortion_corrector_node.param.yaml      |  6 ---
 .../ring_outlier_filter_node.param.yaml       | 14 -------
 .../launch/velodyne_VLP16.launch.xml          | 39 -------------------
 common_awsim_sensor_launch/package.xml        | 22 -----------
 6 files changed, 3 insertions(+), 99 deletions(-)
 delete mode 100644 common_awsim_sensor_launch/CMakeLists.txt
 delete mode 100644 common_awsim_sensor_launch/config/distortion_corrector_node.param.yaml
 delete mode 100644 common_awsim_sensor_launch/config/ring_outlier_filter_node.param.yaml
 delete mode 100644 common_awsim_sensor_launch/launch/velodyne_VLP16.launch.xml
 delete mode 100644 common_awsim_sensor_launch/package.xml

diff --git a/awsim_sensor_kit_launch/launch/lidar.launch.xml b/awsim_sensor_kit_launch/launch/lidar.launch.xml
index 0ed6703..6dcb49a 100644
--- a/awsim_sensor_kit_launch/launch/lidar.launch.xml
+++ b/awsim_sensor_kit_launch/launch/lidar.launch.xml
@@ -11,7 +11,7 @@
 
     <group>
       <push-ros-namespace namespace="top"/>
-      <include file="$(find-pkg-share common_awsim_sensor_launch)/launch/velodyne_VLP16.launch.xml">
+      <include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
         <arg name="max_range" value="250.0"/>
         <arg name="sensor_frame" value="velodyne_top"/>
         <arg name="sensor_ip" value="127.0.0.1"/>
@@ -26,7 +26,7 @@
 
     <group>
       <push-ros-namespace namespace="left"/>
-      <include file="$(find-pkg-share common_awsim_sensor_launch)/launch/velodyne_VLP16.launch.xml">
+      <include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
         <arg name="max_range" value="5.0"/>
         <arg name="sensor_frame" value="velodyne_left"/>
         <arg name="sensor_ip" value="127.0.0.1"/>
@@ -43,7 +43,7 @@
 
     <group>
       <push-ros-namespace namespace="right"/>
-      <include file="$(find-pkg-share common_awsim_sensor_launch)/launch/velodyne_VLP16.launch.xml">
+      <include file="$(find-pkg-share common_sensor_launch)/launch/velodyne_VLP16.launch.xml">
         <arg name="max_range" value="5.0"/>
         <arg name="sensor_frame" value="velodyne_right"/>
         <arg name="sensor_ip" value="127.0.0.1"/>
diff --git a/common_awsim_sensor_launch/CMakeLists.txt b/common_awsim_sensor_launch/CMakeLists.txt
deleted file mode 100644
index 8a9a6a0..0000000
--- a/common_awsim_sensor_launch/CMakeLists.txt
+++ /dev/null
@@ -1,15 +0,0 @@
-cmake_minimum_required(VERSION 3.5)
-project(common_awsim_sensor_launch)
-
-find_package(ament_cmake_auto REQUIRED)
-ament_auto_find_build_dependencies()
-
-if(BUILD_TESTING)
-  find_package(ament_lint_auto REQUIRED)
-  ament_lint_auto_find_test_dependencies()
-endif()
-
-ament_auto_package(INSTALL_TO_SHARE
-  config
-  launch
-)
diff --git a/common_awsim_sensor_launch/config/distortion_corrector_node.param.yaml b/common_awsim_sensor_launch/config/distortion_corrector_node.param.yaml
deleted file mode 100644
index c558756..0000000
--- a/common_awsim_sensor_launch/config/distortion_corrector_node.param.yaml
+++ /dev/null
@@ -1,6 +0,0 @@
-/**:
-  ros__parameters:
-    base_frame: base_link
-    use_imu: true
-    use_3d_distortion_correction: false
-    update_azimuth_and_distance: false
diff --git a/common_awsim_sensor_launch/config/ring_outlier_filter_node.param.yaml b/common_awsim_sensor_launch/config/ring_outlier_filter_node.param.yaml
deleted file mode 100644
index 76bf689..0000000
--- a/common_awsim_sensor_launch/config/ring_outlier_filter_node.param.yaml
+++ /dev/null
@@ -1,14 +0,0 @@
-/**:
-  ros__parameters:
-    distance_ratio: 1.03
-    object_length_threshold: 0.1
-    num_points_threshold: 4
-    max_rings_num: 128
-    max_points_num_per_ring: 4000
-    publish_outlier_pointcloud: false
-    min_azimuth_deg: 0.0
-    max_azimuth_deg: 360.0
-    max_distance: 12.0
-    vertical_bins: 128
-    horizontal_bins: 36
-    noise_threshold: 2
diff --git a/common_awsim_sensor_launch/launch/velodyne_VLP16.launch.xml b/common_awsim_sensor_launch/launch/velodyne_VLP16.launch.xml
deleted file mode 100644
index a304af0..0000000
--- a/common_awsim_sensor_launch/launch/velodyne_VLP16.launch.xml
+++ /dev/null
@@ -1,39 +0,0 @@
-<launch>
-
-  <!-- Params -->
-  <arg name="launch_driver" default="true"/>
-
-  <arg name="model" default="VLP16"/>
-  <arg name="max_range" default="130.0"/>
-  <arg name="min_range" default="0.4"/>
-  <arg name="sensor_frame" default="velodyne"/>
-  <arg name="return_mode" default="SingleStrongest"/>
-  <arg name="sensor_ip" default="192.168.1.201"/>
-  <arg name="host_ip" default="255.255.255.255"/>
-  <arg name="data_port" default="2368"/>
-  <arg name="scan_phase" default="0.0"/>
-  <arg name="cloud_min_angle" default="0"/>
-  <arg name="cloud_max_angle" default="360"/>
-  <arg name="vehicle_mirror_param_file"/>
-  <arg name="container_name" default="velodyne_node_container"/>
-
-  <include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
-    <arg name="launch_driver" value="$(var launch_driver)"/>
-    <arg name="sensor_model" value="$(var model)"/>
-    <arg name="return_mode" value="$(var return_mode)"/>
-    <arg name="max_range" value="$(var max_range)"/>
-    <arg name="min_range" value="$(var min_range)"/>
-    <arg name="frame_id" value="$(var sensor_frame)"/>
-    <arg name="sensor_ip" value="$(var sensor_ip)"/>
-    <arg name="host_ip" value="$(var host_ip)"/>
-    <arg name="data_port" value="$(var data_port)"/>
-    <arg name="scan_phase" value="$(var scan_phase)"/>
-    <arg name="cloud_min_angle" value="$(var cloud_min_angle)"/>
-    <arg name="cloud_max_angle" value="$(var cloud_max_angle)"/>
-    <arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
-    <arg name="use_intra_process" value="true"/>
-    <arg name="use_multithread" value="true"/>
-    <arg name="container_name" value="$(var container_name)"/>
-  </include>
-
-</launch>
diff --git a/common_awsim_sensor_launch/package.xml b/common_awsim_sensor_launch/package.xml
deleted file mode 100644
index 1d83e1d..0000000
--- a/common_awsim_sensor_launch/package.xml
+++ /dev/null
@@ -1,22 +0,0 @@
-<?xml version="1.0"?>
-<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
-<package format="3">
-  <name>common_awsim_sensor_launch</name>
-  <version>0.1.0</version>
-  <description>The common_sensor_launch package</description>
-  <maintainer email="piotr.jaroszek@robotec.ai">Piotr Jaroszek</maintainer>
-  <license>Apache License 2.0</license>
-
-  <buildtool_depend>ament_cmake_auto</buildtool_depend>
-
-  <exec_depend>velodyne_driver</exec_depend>
-  <exec_depend>velodyne_monitor</exec_depend>
-  <exec_depend>velodyne_pointcloud</exec_depend>
-
-  <test_depend>ament_lint_auto</test_depend>
-  <test_depend>autoware_lint_common</test_depend>
-
-  <export>
-    <build_type>ament_cmake</build_type>
-  </export>
-</package>