diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index 46301f787193f..7d8344c24819c 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -106,19 +106,19 @@ void PerceptionOnlineEvaluatorNode::toMetricMsg( // min value metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build() .name(metric + "/min") - .unit("m") + .unit("") .value(std::to_string(metric_stat.min()))); // max value metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build() .name(metric + "/max") - .unit("m") + .unit("") .value(std::to_string(metric_stat.max()))); // mean value metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build() .name(metric + "/mean") - .unit("m") + .unit("") .value(std::to_string(metric_stat.mean()))); } @@ -126,9 +126,10 @@ void PerceptionOnlineEvaluatorNode::toMetricMsg( const std::string & metric, const double metric_value, tier4_metric_msgs::msg::MetricArray & metrics_msg) const { - metrics_msg.metric_array.emplace_back( - tier4_metric_msgs::build().name(metric).unit("m").value( - std::to_string(metric_value))); + metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build() + .name(metric + "/metric_value") + .unit("") + .value(std::to_string(metric_value))); } void PerceptionOnlineEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg)