From 68f9ddb95661b9dd17ad94a2ca9f82f8b9cb1c17 Mon Sep 17 00:00:00 2001
From: Motsu-san <masahiro.sakamoto@tier4.jp>
Date: Mon, 29 Jan 2024 21:41:43 +0900
Subject: [PATCH 1/5] refactor: Create .yaml file for default parameters of
 transform_maps.launch.xml

Signed-off-by: Motsu-san <masahiro.sakamoto@tier4.jp>
---
 map/util/lanelet2_map_preprocessor/CMakeLists.txt  |  1 +
 .../config/transform_maps.param.yaml               |  8 ++++++++
 .../launch/transform_maps.launch.xml               | 14 ++------------
 .../src/transform_maps.cpp                         | 12 ++++++------
 4 files changed, 17 insertions(+), 18 deletions(-)
 create mode 100644 map/util/lanelet2_map_preprocessor/config/transform_maps.param.yaml

diff --git a/map/util/lanelet2_map_preprocessor/CMakeLists.txt b/map/util/lanelet2_map_preprocessor/CMakeLists.txt
index 8a6b16c05011b..982a262455efa 100644
--- a/map/util/lanelet2_map_preprocessor/CMakeLists.txt
+++ b/map/util/lanelet2_map_preprocessor/CMakeLists.txt
@@ -29,5 +29,6 @@ if(BUILD_TESTING)
 endif()
 
 ament_auto_package(INSTALL_TO_SHARE
+  config
   launch
 )
diff --git a/map/util/lanelet2_map_preprocessor/config/transform_maps.param.yaml b/map/util/lanelet2_map_preprocessor/config/transform_maps.param.yaml
new file mode 100644
index 0000000000000..04ef7ad2cccd1
--- /dev/null
+++ b/map/util/lanelet2_map_preprocessor/config/transform_maps.param.yaml
@@ -0,0 +1,8 @@
+/**:
+  ros__parameters:
+    x: 0.0
+    y: 0.0
+    z: 0.0
+    roll: 0.0
+    pitch: 0.0
+    yaw: 0.0
diff --git a/map/util/lanelet2_map_preprocessor/launch/transform_maps.launch.xml b/map/util/lanelet2_map_preprocessor/launch/transform_maps.launch.xml
index 902ca982dace1..c48f54de2f323 100644
--- a/map/util/lanelet2_map_preprocessor/launch/transform_maps.launch.xml
+++ b/map/util/lanelet2_map_preprocessor/launch/transform_maps.launch.xml
@@ -4,23 +4,13 @@
   <arg name="pcd_map_path" default=""/>
   <arg name="llt_output_path" default=""/>
   <arg name="pcd_output_path" default=""/>
-  <arg name="x" default="0.0"/>
-  <arg name="y" default="0.0"/>
-  <arg name="z" default="0.0"/>
-  <arg name="roll" default="0.0"/>
-  <arg name="pitch" default="0.0"/>
-  <arg name="yaw" default="0.0"/>
+  <arg name="param_file" default="$(find-pkg-share lanelet2_map_preprocessor)/config/transform_maps.param.yaml"/>
 
   <node pkg="lanelet2_map_preprocessor" exec="transform_maps" name="transform_maps" output="screen">
     <param name="llt_map_path" value="$(var llt_map_path)"/>
     <param name="pcd_map_path" value="$(var pcd_map_path)"/>
     <param name="llt_output_path" value="$(var llt_output_path)"/>
     <param name="pcd_output_path" value="$(var pcd_output_path)"/>
-    <param name="x" value="$(var x)"/>
-    <param name="y" value="$(var y)"/>
-    <param name="z" value="$(var z)"/>
-    <param name="roll" value="$(var roll)"/>
-    <param name="pitch" value="$(var pitch)"/>
-    <param name="yaw" value="$(var yaw)"/>
+    <param from="$(var param_file)"/>
   </node>
 </launch>
diff --git a/map/util/lanelet2_map_preprocessor/src/transform_maps.cpp b/map/util/lanelet2_map_preprocessor/src/transform_maps.cpp
index 987f559be1e8e..2317ddb7d9f95 100644
--- a/map/util/lanelet2_map_preprocessor/src/transform_maps.cpp
+++ b/map/util/lanelet2_map_preprocessor/src/transform_maps.cpp
@@ -107,12 +107,12 @@ int main(int argc, char * argv[])
   const auto pcd_map_path = node->declare_parameter<std::string>("pcd_map_path");
   const auto llt_output_path = node->declare_parameter<std::string>("llt_output_path");
   const auto pcd_output_path = node->declare_parameter<std::string>("pcd_output_path");
-  const auto x = node->declare_parameter<double>("x", 0.0);
-  const auto y = node->declare_parameter<double>("y", 0.0);
-  const auto z = node->declare_parameter<double>("z", 0.0);
-  const auto roll = node->declare_parameter<double>("roll", 0.0);
-  const auto pitch = node->declare_parameter<double>("pitch", 0.0);
-  const auto yaw = node->declare_parameter<double>("yaw", 0.0);
+  const auto x = node->declare_parameter<double>("x");
+  const auto y = node->declare_parameter<double>("y");
+  const auto z = node->declare_parameter<double>("z");
+  const auto roll = node->declare_parameter<double>("roll");
+  const auto pitch = node->declare_parameter<double>("pitch");
+  const auto yaw = node->declare_parameter<double>("yaw");
 
   std::cout << "transforming maps with following parameters" << std::endl
             << "x " << x << std::endl

From 1f937490771511051a490cdbc7b2291abf0edc3a Mon Sep 17 00:00:00 2001
From: Motsu-san <masahiro.sakamoto@tier4.jp>
Date: Mon, 29 Jan 2024 21:42:57 +0900
Subject: [PATCH 2/5] refactor: Create JSON Schema file of transform_maps

Signed-off-by: Motsu-san <masahiro.sakamoto@tier4.jp>
---
 .../schema/transform_maps.schema.json         | 86 +++++++++++++++++++
 1 file changed, 86 insertions(+)
 create mode 100644 map/util/lanelet2_map_preprocessor/schema/transform_maps.schema.json

diff --git a/map/util/lanelet2_map_preprocessor/schema/transform_maps.schema.json b/map/util/lanelet2_map_preprocessor/schema/transform_maps.schema.json
new file mode 100644
index 0000000000000..4c86e8a72c110
--- /dev/null
+++ b/map/util/lanelet2_map_preprocessor/schema/transform_maps.schema.json
@@ -0,0 +1,86 @@
+{
+  "$schema": "http://json-schema.org/draft-07/schema#",
+  "title": "Parameters for Transforming Maps",
+  "type": "object",
+  "definitions": {
+    "transform_maps": {
+      "type": "object",
+      "properties": {
+        "llt_map_path": {
+          "type": "string",
+          "description": "Path pointing to the input lanelet2 file",
+          "default": ""
+        },
+        "pcd_map_path": {
+          "type": "string",
+          "description": "Path pointing to the input point cloud file",
+          "default": ""
+        },
+        "llt_output_path": {
+          "type": "string",
+          "description": "Path pointing to the output lanelet2 file",
+          "default": ""
+        },
+        "pcd_output_path": {
+          "type": "string",
+          "description": "Path pointing to the output point cloud file",
+          "default": ""
+        },
+        "x": {
+          "type": "number",
+          "default": 0.0,
+          "description": "x factor of Translation vector for transforming maps [m]"
+        },
+        "y": {
+          "type": "number",
+          "default": 0.0,
+          "description": "y factor of Translation vector for transforming maps [m]"
+        },
+        "z": {
+          "type": "number",
+          "default": 0.0,
+          "description": "z factor of Translation vector for transforming maps [m]"
+        },
+        "roll": {
+          "type": "number",
+          "default": 0.0,
+          "description": "roll factor of Rotation vector for transforming maps [rad]"
+        },
+        "pitch": {
+          "type": "number",
+          "default": 0.0,
+          "description": "pitch factor of Rotation vector for transforming maps [rad]"
+        },
+        "yaw": {
+          "type": "number",
+          "default": 0.0,
+          "description": "yaw factor of Rotation vector for transforming maps [rad]"
+        }
+      },
+      "required": [
+        "x",
+        "y",
+        "z",
+        "roll",
+        "pitch",
+        "yaw"
+      ]
+    }
+  },
+  "properties": {
+    "/**": {
+      "type": "object",
+      "properties": {
+        "ros__parameters": {
+          "$ref": "#/definitions/transform_maps"
+        }
+      },
+      "required": [
+        "ros__parameters"
+      ]
+    }
+  },
+  "required": [
+    "/**"
+  ]
+}

From 272380d98aee7b0169206f76db7d315cbc7126a7 Mon Sep 17 00:00:00 2001
From: Motsu-san <masahiro.sakamoto@tier4.jp>
Date: Thu, 1 Feb 2024 17:08:08 +0900
Subject: [PATCH 3/5] refactor: Replace .launch path parameters to .yaml ones

Signed-off-by: Motsu-san <masahiro.sakamoto@tier4.jp>
---
 .../config/transform_maps.param.yaml                 |  4 ++++
 .../launch/transform_maps.launch.xml                 | 12 +-----------
 2 files changed, 5 insertions(+), 11 deletions(-)

diff --git a/map/util/lanelet2_map_preprocessor/config/transform_maps.param.yaml b/map/util/lanelet2_map_preprocessor/config/transform_maps.param.yaml
index 04ef7ad2cccd1..548c28055c834 100644
--- a/map/util/lanelet2_map_preprocessor/config/transform_maps.param.yaml
+++ b/map/util/lanelet2_map_preprocessor/config/transform_maps.param.yaml
@@ -1,5 +1,9 @@
 /**:
   ros__parameters:
+    llt_map_path: $(var llt_map_path)
+    pcd_map_path: $(var pcd_map_path)
+    llt_output_path: $(var llt_output_path)
+    pcd_output_path: $(var pcd_output_path)
     x: 0.0
     y: 0.0
     z: 0.0
diff --git a/map/util/lanelet2_map_preprocessor/launch/transform_maps.launch.xml b/map/util/lanelet2_map_preprocessor/launch/transform_maps.launch.xml
index c48f54de2f323..950593771878c 100644
--- a/map/util/lanelet2_map_preprocessor/launch/transform_maps.launch.xml
+++ b/map/util/lanelet2_map_preprocessor/launch/transform_maps.launch.xml
@@ -1,16 +1,6 @@
 <?xml version="1.0" encoding="UTF-8"?>
 <launch>
-  <arg name="llt_map_path" default=""/>
-  <arg name="pcd_map_path" default=""/>
-  <arg name="llt_output_path" default=""/>
-  <arg name="pcd_output_path" default=""/>
-  <arg name="param_file" default="$(find-pkg-share lanelet2_map_preprocessor)/config/transform_maps.param.yaml"/>
-
   <node pkg="lanelet2_map_preprocessor" exec="transform_maps" name="transform_maps" output="screen">
-    <param name="llt_map_path" value="$(var llt_map_path)"/>
-    <param name="pcd_map_path" value="$(var pcd_map_path)"/>
-    <param name="llt_output_path" value="$(var llt_output_path)"/>
-    <param name="pcd_output_path" value="$(var pcd_output_path)"/>
-    <param from="$(var param_file)"/>
+    <param from="$(find-pkg-share lanelet2_map_preprocessor)/config/transform_maps.param.yaml" allow_substs="true"/>
   </node>
 </launch>

From fbef4e13cfa2e6e80f100d622b5f293f970305ff Mon Sep 17 00:00:00 2001
From: Motsu-san <masahiro.sakamoto@tier4.jp>
Date: Fri, 2 Feb 2024 20:37:34 +0900
Subject: [PATCH 4/5] refactor: Create .yaml file for default parameters of
 fix_z_value_by_pcd.launch.xml

Signed-off-by: Motsu-san <masahiro.sakamoto@tier4.jp>
---
 .../config/fix_z_value_by_pcd.param.yaml                  | 5 +++++
 .../launch/fix_z_value_by_pcd.launch.xml                  | 8 +-------
 2 files changed, 6 insertions(+), 7 deletions(-)
 create mode 100644 map/util/lanelet2_map_preprocessor/config/fix_z_value_by_pcd.param.yaml

diff --git a/map/util/lanelet2_map_preprocessor/config/fix_z_value_by_pcd.param.yaml b/map/util/lanelet2_map_preprocessor/config/fix_z_value_by_pcd.param.yaml
new file mode 100644
index 0000000000000..de86ef7936d74
--- /dev/null
+++ b/map/util/lanelet2_map_preprocessor/config/fix_z_value_by_pcd.param.yaml
@@ -0,0 +1,5 @@
+/**:
+  ros__parameters:
+    llt_map_path: $(var llt_map_path)
+    pcd_map_path: $(var pcd_map_path)
+    llt_output_path: $(var llt_output_path)
diff --git a/map/util/lanelet2_map_preprocessor/launch/fix_z_value_by_pcd.launch.xml b/map/util/lanelet2_map_preprocessor/launch/fix_z_value_by_pcd.launch.xml
index 82021ff25d240..5b2aa2e425184 100644
--- a/map/util/lanelet2_map_preprocessor/launch/fix_z_value_by_pcd.launch.xml
+++ b/map/util/lanelet2_map_preprocessor/launch/fix_z_value_by_pcd.launch.xml
@@ -1,12 +1,6 @@
 <?xml version="1.0" encoding="UTF-8"?>
 <launch>
-  <arg name="llt_map_path" default=""/>
-  <arg name="pcd_map_path" default=""/>
-  <arg name="llt_output_path" default=""/>
-
   <node pkg="lanelet2_map_preprocessor" exec="fix_z_value_by_pcd" name="fix_z_value_by_pcd" output="screen">
-    <param name="llt_map_path" value="$(var llt_map_path)"/>
-    <param name="pcd_map_path" value="$(var pcd_map_path)"/>
-    <param name="llt_output_path" value="$(var llt_output_path)"/>
+    <param from="$(find-pkg-share lanelet2_map_preprocessor)/config/fix_z_value_by_pcd.param.yaml" allow_substs="true"/>
   </node>
 </launch>

From 5a710ccef60841c7106a71550da2feb974fcbb7a Mon Sep 17 00:00:00 2001
From: "pre-commit-ci[bot]"
 <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Date: Wed, 14 Feb 2024 07:26:40 +0000
Subject: [PATCH 5/5] style(pre-commit): autofix

---
 .../schema/transform_maps.schema.json           | 17 +++--------------
 1 file changed, 3 insertions(+), 14 deletions(-)

diff --git a/map/util/lanelet2_map_preprocessor/schema/transform_maps.schema.json b/map/util/lanelet2_map_preprocessor/schema/transform_maps.schema.json
index 4c86e8a72c110..78fb3952d44ce 100644
--- a/map/util/lanelet2_map_preprocessor/schema/transform_maps.schema.json
+++ b/map/util/lanelet2_map_preprocessor/schema/transform_maps.schema.json
@@ -57,14 +57,7 @@
           "description": "yaw factor of Rotation vector for transforming maps [rad]"
         }
       },
-      "required": [
-        "x",
-        "y",
-        "z",
-        "roll",
-        "pitch",
-        "yaw"
-      ]
+      "required": ["x", "y", "z", "roll", "pitch", "yaw"]
     }
   },
   "properties": {
@@ -75,12 +68,8 @@
           "$ref": "#/definitions/transform_maps"
         }
       },
-      "required": [
-        "ros__parameters"
-      ]
+      "required": ["ros__parameters"]
     }
   },
-  "required": [
-    "/**"
-  ]
+  "required": ["/**"]
 }