Skip to content

Commit 94f2ae4

Browse files
committed
refactor: Create .yaml file for default parameters of transform_maps.launch.xml
Signed-off-by: Motsu-san <masahiro.sakamoto@tier4.jp>
1 parent 7022620 commit 94f2ae4

File tree

4 files changed

+17
-18
lines changed

4 files changed

+17
-18
lines changed

map/util/lanelet2_map_preprocessor/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -29,5 +29,6 @@ if(BUILD_TESTING)
2929
endif()
3030

3131
ament_auto_package(INSTALL_TO_SHARE
32+
config
3233
launch
3334
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
/**:
2+
ros__parameters:
3+
x: 0.0
4+
y: 0.0
5+
z: 0.0
6+
roll: 0.0
7+
pitch: 0.0
8+
yaw: 0.0

map/util/lanelet2_map_preprocessor/launch/transform_maps.launch.xml

+2-12
Original file line numberDiff line numberDiff line change
@@ -4,23 +4,13 @@
44
<arg name="pcd_map_path" default=""/>
55
<arg name="llt_output_path" default=""/>
66
<arg name="pcd_output_path" default=""/>
7-
<arg name="x" default="0.0"/>
8-
<arg name="y" default="0.0"/>
9-
<arg name="z" default="0.0"/>
10-
<arg name="roll" default="0.0"/>
11-
<arg name="pitch" default="0.0"/>
12-
<arg name="yaw" default="0.0"/>
7+
<arg name="param_file" default="$(find-pkg-share lanelet2_map_preprocessor)/config/transform_maps.param.yaml"/>
138

149
<node pkg="lanelet2_map_preprocessor" exec="transform_maps" name="transform_maps" output="screen">
1510
<param name="llt_map_path" value="$(var llt_map_path)"/>
1611
<param name="pcd_map_path" value="$(var pcd_map_path)"/>
1712
<param name="llt_output_path" value="$(var llt_output_path)"/>
1813
<param name="pcd_output_path" value="$(var pcd_output_path)"/>
19-
<param name="x" value="$(var x)"/>
20-
<param name="y" value="$(var y)"/>
21-
<param name="z" value="$(var z)"/>
22-
<param name="roll" value="$(var roll)"/>
23-
<param name="pitch" value="$(var pitch)"/>
24-
<param name="yaw" value="$(var yaw)"/>
14+
<param from="$(var param_file)"/>
2515
</node>
2616
</launch>

map/util/lanelet2_map_preprocessor/src/transform_maps.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -107,12 +107,12 @@ int main(int argc, char * argv[])
107107
const auto pcd_map_path = node->declare_parameter<std::string>("pcd_map_path");
108108
const auto llt_output_path = node->declare_parameter<std::string>("llt_output_path");
109109
const auto pcd_output_path = node->declare_parameter<std::string>("pcd_output_path");
110-
const auto x = node->declare_parameter<double>("x", 0.0);
111-
const auto y = node->declare_parameter<double>("y", 0.0);
112-
const auto z = node->declare_parameter<double>("z", 0.0);
113-
const auto roll = node->declare_parameter<double>("roll", 0.0);
114-
const auto pitch = node->declare_parameter<double>("pitch", 0.0);
115-
const auto yaw = node->declare_parameter<double>("yaw", 0.0);
110+
const auto x = node->declare_parameter<double>("x");
111+
const auto y = node->declare_parameter<double>("y");
112+
const auto z = node->declare_parameter<double>("z");
113+
const auto roll = node->declare_parameter<double>("roll");
114+
const auto pitch = node->declare_parameter<double>("pitch");
115+
const auto yaw = node->declare_parameter<double>("yaw");
116116

117117
std::cout << "transforming maps with following parameters" << std::endl
118118
<< "x " << x << std::endl

0 commit comments

Comments
 (0)