@@ -113,7 +113,7 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti
113
113
std::make_unique<autoware_utils::DiagnosticsInterface>(this , " node_processing_time_status" );
114
114
115
115
// diagnostics parameters
116
- max_allowed_processing_time_ = declare_parameter<double >(" max_allowed_processing_time " );
116
+ max_allowed_processing_time_ms_ = declare_parameter<double >(" max_allowed_processing_time_ms " );
117
117
max_acceptable_consecutive_delay_ms_ =
118
118
declare_parameter<double >(" max_acceptable_consecutive_delay_ms" );
119
119
const long validation_callback_interval_ms =
@@ -202,13 +202,13 @@ void LidarCenterPointNode::pointCloudCallback(
202
202
const double processing_time_ms = stop_watch_ptr_->toc (" processing_time" , true );
203
203
204
204
// check processing time is acceptable
205
- if (processing_time_ms > max_allowed_processing_time_ ) {
205
+ if (processing_time_ms > max_allowed_processing_time_ms_ ) {
206
206
diagnostics_interface_ptr_->add_key_value (" is_processing_time_ms_in_expected_range" , false );
207
207
208
208
std::stringstream message;
209
209
message << " CenterPoint processing time exceeds the acceptable limit of "
210
- << max_allowed_processing_time_ << " ms by "
211
- << (processing_time_ms - max_allowed_processing_time_ ) << " ms." ;
210
+ << max_allowed_processing_time_ms_ << " ms by "
211
+ << (processing_time_ms - max_allowed_processing_time_ms_ ) << " ms." ;
212
212
213
213
diagnostics_interface_ptr_->update_level_and_message (
214
214
diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str ());
0 commit comments