diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index c31402662a944..c2893ce7d1f92 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -198,7 +198,7 @@ CrosswalkModule::CrosswalkModule( collision_info_pub_ = node.create_publisher("~/debug/collision_info", 1); - vehicle_stop_checker_ = std::make_unique(&node); + vehicle_stop_checker_ = std::make_unique(&node); } bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 5af97498b1a81..77b422f1bd5da 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -436,7 +436,7 @@ class CrosswalkModule : public SceneModuleInterface // Debug mutable DebugData debug_data_; - std::unique_ptr vehicle_stop_checker_{nullptr}; + std::unique_ptr vehicle_stop_checker_{nullptr}; // Stop watch StopWatch stop_watch_;