From 8b7fe0069b84ef80ad4ed2bd4c55d6ff8ec99fc5 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 23 Jan 2025 00:36:39 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../include/parameter_estimator/debugger.hpp | 8 +++++--- vehicle/parameter_estimator/package.xml | 2 +- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/vehicle/parameter_estimator/include/parameter_estimator/debugger.hpp b/vehicle/parameter_estimator/include/parameter_estimator/debugger.hpp index 265ecf41..5d26c3a5 100644 --- a/vehicle/parameter_estimator/include/parameter_estimator/debugger.hpp +++ b/vehicle/parameter_estimator/include/parameter_estimator/debugger.hpp @@ -33,11 +33,13 @@ struct Debugger rclcpp::QoS durable_qos(queue_size); durable_qos.transient_local(); // option for latching - pub_debug_ = rclcpp::create_publisher( - node, "~/debug_values/" + name, durable_qos); + pub_debug_ = + rclcpp::create_publisher( + node, "~/debug_values/" + name, durable_qos); debug_values_.data.resize(num_debug_values_, 0.0); } - rclcpp::Publisher::SharedPtr pub_debug_; + rclcpp::Publisher::SharedPtr + pub_debug_; void publishDebugValue() { pub_debug_->publish(debug_values_); } static constexpr std::uint8_t num_debug_values_ = 20; mutable autoware_internal_debug_msgs::msg::Float32MultiArrayStamped debug_values_; diff --git a/vehicle/parameter_estimator/package.xml b/vehicle/parameter_estimator/package.xml index c9db2230..d2ff997a 100644 --- a/vehicle/parameter_estimator/package.xml +++ b/vehicle/parameter_estimator/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto + autoware_internal_debug_msgs autoware_vehicle_info_utils autoware_vehicle_msgs estimator_utils @@ -17,7 +18,6 @@ rclcpp sensor_msgs tier4_calibration_msgs - autoware_internal_debug_msgs plotjuggler plotjuggler_ros