Skip to content

Commit 9827374

Browse files
committed
add ms in name
Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com>
1 parent f82a16c commit 9827374

File tree

3 files changed

+6
-6
lines changed

3 files changed

+6
-6
lines changed

perception/autoware_lidar_centerpoint/config/centerpoint_diagnostics.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
ros__parameters:
33
# When the processing time exceeds the max_allowed_processing_time,
44
# a warning will be triggered.
5-
max_allowed_processing_time: 200.0 # in milliseconds
5+
max_allowed_processing_time_ms: 200.0 # in milliseconds
66
# If the warning is triggered and if a timestamp of last normal processing is more than
77
# max_acceptable_consecutive_delay_ms, an error diagnostic message will be sent.
88
max_acceptable_consecutive_delay_ms: 1000.0

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ class LidarCenterPointNode : public rclcpp::Node
5959
bool has_twist_{false};
6060

6161
bool is_processing_delayed_{false};
62-
double max_allowed_processing_time_;
62+
double max_allowed_processing_time_ms_;
6363
double max_acceptable_consecutive_delay_ms_;
6464
// set optional to avoid sending the error diagnostics before node start processing
6565
std::optional<rclcpp::Time> last_normal_processing_timestamp_;

perception/autoware_lidar_centerpoint/src/node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,7 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti
113113
std::make_unique<autoware_utils::DiagnosticsInterface>(this, "node_processing_time_status");
114114

115115
// 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");
117117
max_acceptable_consecutive_delay_ms_ =
118118
declare_parameter<double>("max_acceptable_consecutive_delay_ms");
119119
const long validation_callback_interval_ms =
@@ -202,13 +202,13 @@ void LidarCenterPointNode::pointCloudCallback(
202202
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
203203

204204
// check processing time is acceptable
205-
if (processing_time_ms > max_allowed_processing_time_) {
205+
if (processing_time_ms > max_allowed_processing_time_ms_) {
206206
diagnostics_interface_ptr_->add_key_value("is_processing_time_ms_in_expected_range", false);
207207

208208
std::stringstream message;
209209
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.";
212212

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

0 commit comments

Comments
 (0)