diff --git a/planning/route_handler/test/route_parser.cpp b/planning/route_handler/test/route_parser.cpp index c8651a9f33b67..ccbf86b700b9e 100644 --- a/planning/route_handler/test/route_parser.cpp +++ b/planning/route_handler/test/route_parser.cpp @@ -55,9 +55,9 @@ std::vector parse_lanelet_primitives(const YAML::Node & node) { std::vector primitives; primitives.reserve(node.size()); - for (const auto & p : node) { - primitives.emplace_back(parse_lanelet_primitive(p)); - } + std::transform(node.begin(), node.end(), std::back_inserter(primitives), [&](const auto & p) { + return parse_lanelet_primitive(p); + }); return primitives; } diff --git a/planning/route_handler/test/test_route_handler.hpp b/planning/route_handler/test/test_route_handler.hpp index 9db07b2020fd8..d8bd41d608c37 100644 --- a/planning/route_handler/test/test_route_handler.hpp +++ b/planning/route_handler/test/test_route_handler.hpp @@ -40,7 +40,7 @@ using autoware_auto_mapping_msgs::msg::HADMapBin; class TestRouteHandler : public ::testing::Test { public: - TestRouteHandler() { route_handler_ = std::make_shared(makeMapBinMsg()); } + TestRouteHandler() : route_handler_(std::make_shared(makeMapBinMsg())) {} TestRouteHandler(const TestRouteHandler &) = delete; TestRouteHandler(TestRouteHandler &&) = delete; TestRouteHandler & operator=(const TestRouteHandler &) = delete;