Skip to content

Commit ed00a05

Browse files
committed
fix clang
Signed-off-by: Shohei Sakai <saka1s.jp@gmail.com>
1 parent 5e65cc1 commit ed00a05

File tree

1 file changed

+6
-4
lines changed

1 file changed

+6
-4
lines changed

planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -333,7 +333,8 @@ void StaticCenterlineGeneratorNode::generate_centerline()
333333
// declare planning setting parameters
334334
const auto lanelet2_input_dir_path = declare_parameter<std::string>("lanelet2_input_dir_path");
335335
if (lanelet2_input_dir_path == "") {
336-
throw std::invalid_argument("The `lanelet2_input_dir_path` is empty. Please set a directory path. (Not a file path)");
336+
throw std::invalid_argument(
337+
"The `lanelet2_input_dir_path` is empty. Please set a directory path. (Not a file path)");
337338
}
338339

339340
// process
@@ -487,8 +488,8 @@ void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_
487488
// load map by the map_loader package
488489
map_bin_ptr_ = [&]() -> LaneletMapBin::ConstSharedPtr {
489490
// load map projector info
490-
map_projector_info_ = std::make_unique<MapProjectorInfo>(
491-
autoware::map_projection_loader::load_map_projector_info(
491+
map_projector_info_ =
492+
std::make_unique<MapProjectorInfo>(autoware::map_projection_loader::load_map_projector_info(
492493
map_projector_info_file_path, lanelet2_map_file_path));
493494
const auto map_ptr = autoware::map_loader::Lanelet2MapLoaderNode::load_map(
494495
lanelet2_map_file_path, *map_projector_info_);
@@ -532,7 +533,8 @@ void StaticCenterlineGeneratorNode::on_load_map(
532533
const LoadMap::Request::SharedPtr request, const LoadMap::Response::SharedPtr response)
533534
{
534535
const std::string tmp_lanelet2_input_dir_path = "/tmp/input_lanelet2_map";
535-
const std::string tmp_lanelet2_input_file_path = tmp_lanelet2_input_dir_path + "/lanelet2_map.osm";
536+
const std::string tmp_lanelet2_input_file_path =
537+
tmp_lanelet2_input_dir_path + "/lanelet2_map.osm";
536538

537539
// create temporary directory
538540
std::filesystem::create_directories(tmp_lanelet2_input_dir_path);

0 commit comments

Comments
 (0)