From 30bd53faaa9c0093f368d1bd8b9930108e4fef3b Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 17 Feb 2022 12:54:48 +0900 Subject: [PATCH] apply clang Signed-off-by: Takamasa Horibe --- .../obstacle_stop_planner/src/adaptive_cruise_control.cpp | 4 ++-- planning/obstacle_stop_planner/src/debug_marker.cpp | 3 ++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp index 61056aa0c489..df4209c6d1c9 100644 --- a/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp +++ b/planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp @@ -179,8 +179,8 @@ AdaptiveCruiseController::AdaptiveCruiseController( param_.rough_velocity_rate = node_->declare_parameter(acc_ns + "rough_velocity_rate", 0.9); /* publisher */ - pub_debug_ = - node_->create_publisher("~/adaptive_cruise_control/debug_values", 1); + pub_debug_ = node_->create_publisher( + "~/adaptive_cruise_control/debug_values", 1); } void AdaptiveCruiseController::insertAdaptiveCruiseVelocity( diff --git a/planning/obstacle_stop_planner/src/debug_marker.cpp b/planning/obstacle_stop_planner/src/debug_marker.cpp index fa7b2795a363..491d2b3dfd90 100644 --- a/planning/obstacle_stop_planner/src/debug_marker.cpp +++ b/planning/obstacle_stop_planner/src/debug_marker.cpp @@ -41,7 +41,8 @@ ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode( node_->create_publisher("~/debug/marker", 1); stop_reason_pub_ = node_->create_publisher("~/output/stop_reasons", 1); - pub_debug_values_ = node_->create_publisher("~/obstacle_stop/debug_values", 1); + pub_debug_values_ = + node_->create_publisher("~/obstacle_stop/debug_values", 1); } bool ObstacleStopPlannerDebugNode::pushPolygon(