Skip to content

Commit d174563

Browse files
style(pre-commit): autofix
1 parent a09d59a commit d174563

File tree

3 files changed

+16
-5
lines changed

3 files changed

+16
-5
lines changed

launch/tier4_map_launch/launch/map.launch.xml

+6-1
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,12 @@
6363
<remap from="output/lanelet2_map_marker" to="vector_map_marker"/>
6464
</composable_node>
6565

66-
<composable_node pkg="autoware_lanelet2_map_visualizer" plugin="autoware::lanelet2_map_visualizer::Lanelet2MapVisualizationNode" name="dynamic_lanelet2_map_visualization" if="$(var enable_differential_map_loading)">
66+
<composable_node
67+
pkg="autoware_lanelet2_map_visualizer"
68+
plugin="autoware::lanelet2_map_visualizer::Lanelet2MapVisualizationNode"
69+
name="dynamic_lanelet2_map_visualization"
70+
if="$(var enable_differential_map_loading)"
71+
>
6772
<remap from="input/lanelet2_map" to="/map/dynamic_vector_map"/>
6873
<remap from="output/lanelet2_map_marker" to="/map/dynamic_vector_map_marker"/>
6974
</composable_node>

map/autoware_map_loader/schema/lanelet2_map_loader.schema.json

+8-2
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,15 @@
3030
"type": "string",
3131
"description": "The lanelet2 map path pointing to the .osm file or directory that contains multiple .osm files",
3232
"default": ""
33-
},
33+
}
3434
},
35-
"required": ["enable_differential_map_loading", "allow_unsupported_version", "center_line_resolution", "use_waypoints", "lanelet2_map_path"],
35+
"required": [
36+
"enable_differential_map_loading",
37+
"allow_unsupported_version",
38+
"center_line_resolution",
39+
"use_waypoints",
40+
"lanelet2_map_path"
41+
],
3642
"additionalProperties": false
3743
}
3844
},

map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -108,8 +108,8 @@ void Lanelet2MapLoaderNode::on_map_projector_info(
108108
const MapProjectorInfo::Message::ConstSharedPtr msg)
109109
{
110110
const auto allow_unsupported_version = get_parameter("allow_unsupported_version").as_bool();
111-
const auto lanelet2_paths_or_directory = std::vector<std::string>{
112-
get_parameter("lanelet2_map_path").as_string()};
111+
const auto lanelet2_paths_or_directory =
112+
std::vector<std::string>{get_parameter("lanelet2_map_path").as_string()};
113113
const auto center_line_resolution = get_parameter("center_line_resolution").as_double();
114114
const auto use_waypoints = get_parameter("use_waypoints").as_bool();
115115
const auto enable_differential_map_loading =

0 commit comments

Comments
 (0)