Skip to content

Commit cbedc0f

Browse files
style(pre-commit): autofix
1 parent 9653f0b commit cbedc0f

File tree

2 files changed

+4
-4
lines changed
  • perception/autoware_lidar_centerpoint

2 files changed

+4
-4
lines changed

perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/node.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ class LidarCenterPointNode : public rclcpp::Node
5757
bool has_twist_{false};
5858
float max_allowed_processing_time_;
5959
int max_consecutive_warn_count_;
60-
int consecutive_delay_count_=0;
60+
int consecutive_delay_count_ = 0;
6161

6262
NonMaximumSuppression iou_bev_nms_;
6363
DetectionClassRemapper detection_class_remapper_;

perception/autoware_lidar_centerpoint/src/node.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -196,11 +196,11 @@ void LidarCenterPointNode::pointCloudCallback(
196196

197197
consecutive_delay_count_++;
198198

199-
if(consecutive_delay_count_ <= max_consecutive_warn_count_){
199+
if (consecutive_delay_count_ <= max_consecutive_warn_count_) {
200200
std::stringstream message;
201201
message << "CenterPoint processing time exceeds the acceptable limit of "
202-
<< max_allowed_processing_time_ << " ms by "
203-
<< (processing_time_ms - max_allowed_processing_time_) << " ms.";
202+
<< max_allowed_processing_time_ << " ms by "
203+
<< (processing_time_ms - max_allowed_processing_time_) << " ms.";
204204

205205
diagnostics_interface_ptr_->update_level_and_message(
206206
diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str());

0 commit comments

Comments
 (0)