From 6717fb225cc5533a65bade6245ff47217ec5eb43 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 19:14:10 +0900 Subject: [PATCH] fix(autoware_behavior_velocity_planner): fix clang-diagnostic-format-security (#9411) fix: clang-diagnostic-format-security Signed-off-by: kobayu858 --- .../autoware_behavior_velocity_planner/src/node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp index 394412a508d41..5f4d0606abfc6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp @@ -233,7 +233,7 @@ bool BehaviorVelocityPlannerNode::processData(rclcpp::Clock clock) bool is_ready = true; const auto & logData = [&clock, this](const std::string & data_type) { std::string msg = "Waiting for " + data_type + " data"; - RCLCPP_INFO_THROTTLE(get_logger(), clock, logger_throttle_interval, msg.c_str()); + RCLCPP_INFO_THROTTLE(get_logger(), clock, logger_throttle_interval, "%s", msg.c_str()); }; const auto & getData = [&logData](auto & dest, auto & sub, const std::string & data_type = "") {