From 18679f35869b600c5a67ec937130c2935d6e40d7 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 8 Oct 2024 09:29:19 +0000 Subject: [PATCH] style(pre-commit): autofix Signed-off-by: KeiNakazato --- vehicle/calibration_adapter/src/calibration_adapter_node.cpp | 3 +-- .../parameter_estimator/config/parameter_estimator_param.yaml | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/vehicle/calibration_adapter/src/calibration_adapter_node.cpp b/vehicle/calibration_adapter/src/calibration_adapter_node.cpp index 6cade173..41e9205c 100644 --- a/vehicle/calibration_adapter/src/calibration_adapter_node.cpp +++ b/vehicle/calibration_adapter/src/calibration_adapter_node.cpp @@ -38,8 +38,7 @@ CalibrationAdapterNode::CalibrationAdapterNode() create_publisher("~/output/acceleration_status", durable_qos); pub_acceleration_cmd_ = create_publisher("~/output/acceleration_cmd", durable_qos); - pub_vehicle_twist_ = - create_publisher("~/output/vehicle_twist", durable_qos); + pub_vehicle_twist_ = create_publisher("~/output/vehicle_twist", durable_qos); sub_control_cmd_ = create_subscription( "~/input/control_cmd", queue_size, diff --git a/vehicle/parameter_estimator/config/parameter_estimator_param.yaml b/vehicle/parameter_estimator/config/parameter_estimator_param.yaml index 6649efc9..56594635 100644 --- a/vehicle/parameter_estimator/config/parameter_estimator_param.yaml +++ b/vehicle/parameter_estimator/config/parameter_estimator_param.yaml @@ -6,4 +6,4 @@ parameter_estimator: valid_max_steer_rad: 0.05 # Used as steer data validation, the data should be less than this value valid_min_velocity: 0.5 # Used as velocity validation, the data should be more than this value valid_min_angular_velocity: 0.1 # Used in gear ratio estimator, the angular should be more than this value - gear_ratio: [15.7, 0.053, 0.047] # Initial estimated gear ratio \ No newline at end of file + gear_ratio: [15.7, 0.053, 0.047] # Initial estimated gear ratio