Skip to content

Commit f82a16c

Browse files
style(pre-commit): autofix
1 parent c11a2c6 commit f82a16c

File tree

1 file changed

+8
-6
lines changed
  • perception/autoware_lidar_centerpoint/src

1 file changed

+8
-6
lines changed

perception/autoware_lidar_centerpoint/src/node.cpp

+8-6
Original file line numberDiff line numberDiff line change
@@ -244,20 +244,22 @@ void LidarCenterPointNode::pointCloudCallback(
244244

245245
// Check the timestamp of consecutively delayed processing
246246
// If the node is consistently delayed, publish an error diagnostic message
247-
void LidarCenterPointNode::diagnosticsTimerCallback() {
247+
void LidarCenterPointNode::diagnosticsTimerCallback()
248+
{
248249
// skip if the node has not performed inference yet
249250
if (last_normal_processing_timestamp_) {
250251
diagnostics_processing_delay_->clear();
251252

252253
const rclcpp::Time timestamp_now = this->get_clock()->now();
253254
const double delayed_state_duration =
254-
std::chrono::duration<double, std::milli>(
255-
std::chrono::nanoseconds(
256-
(timestamp_now - last_normal_processing_timestamp_.value()).nanoseconds()))
257-
.count();
255+
std::chrono::duration<double, std::milli>(
256+
std::chrono::nanoseconds(
257+
(timestamp_now - last_normal_processing_timestamp_.value()).nanoseconds()))
258+
.count();
258259

259260
if (delayed_state_duration > max_acceptable_consecutive_delay_ms_) {
260-
diagnostics_processing_delay_->add_key_value("is_processing_time_ms_in_expected_range", false);
261+
diagnostics_processing_delay_->add_key_value(
262+
"is_processing_time_ms_in_expected_range", false);
261263
diagnostics_processing_delay_->update_level_and_message(
262264
diagnostic_msgs::msg::DiagnosticStatus::ERROR,
263265
"CenterPoint processing delay has exceeded the acceptable limit continuously.");

0 commit comments

Comments
 (0)