diff --git a/planning/behavior_velocity_run_out_module/src/debug.cpp b/planning/behavior_velocity_run_out_module/src/debug.cpp index 23764bc73fbff..3f6935365c1a4 100644 --- a/planning/behavior_velocity_run_out_module/src/debug.cpp +++ b/planning/behavior_velocity_run_out_module/src/debug.cpp @@ -73,6 +73,8 @@ visualization_msgs::msg::MarkerArray createPolygonMarkerArray( RunOutDebug::RunOutDebug(rclcpp::Node & node) : node_(node) { + accel_reason_ = AccelReason::UNKNOWN; + pub_debug_values_ = node.create_publisher("~/debug/run_out/debug_values", 1); pub_accel_reason_ = node.create_publisher("~/debug/run_out/accel_reason", 1); diff --git a/planning/behavior_velocity_run_out_module/src/debug.hpp b/planning/behavior_velocity_run_out_module/src/debug.hpp index e9b269ee437f0..fbf682279e363 100644 --- a/planning/behavior_velocity_run_out_module/src/debug.hpp +++ b/planning/behavior_velocity_run_out_module/src/debug.hpp @@ -86,6 +86,7 @@ class RunOutDebug NO_OBSTACLE = 1, PASS = 2, LOW_JERK = 3, + UNKNOWN = 4, }; struct TextWithPosition