Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(perception_online_evaluator): use tier4_metric_msgs instead of diagnostic_msgs #9485

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions evaluator/perception_online_evaluator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -155,11 +155,11 @@ where:

## Inputs / Outputs

| Name | Type | Description |
| ----------------- | ------------------------------------------------- | ------------------------------------------------- |
| `~/input/objects` | `autoware_perception_msgs::msg::PredictedObjects` | The predicted objects to evaluate. |
| `~/metrics` | `diagnostic_msgs::msg::DiagnosticArray` | Diagnostic information about perception accuracy. |
| `~/markers` | `visualization_msgs::msg::MarkerArray` | Visual markers for debugging and visualization. |
| Name | Type | Description |
| ----------------- | ------------------------------------------------- | ----------------------------------------------- |
| `~/input/objects` | `autoware_perception_msgs::msg::PredictedObjects` | The predicted objects to evaluate. |
| `~/metrics` | `tier4_metric_msgs::msg::MetricArray` | Metric information about perception accuracy. |
| `~/markers` | `visualization_msgs::msg::MarkerArray` | Visual markers for debugging and visualization. |

## Parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,10 @@
#include "tf2_ros/transform_listener.h"

#include "autoware_perception_msgs/msg/predicted_objects.hpp"
#include "diagnostic_msgs/msg/diagnostic_array.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "visualization_msgs/msg/marker_array.hpp"
#include <tier4_metric_msgs/msg/metric.hpp>
#include <tier4_metric_msgs/msg/metric_array.hpp>

#include <array>
#include <deque>
Expand All @@ -38,8 +39,6 @@ namespace perception_diagnostics
using autoware::universe_utils::Accumulator;
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObjects;
using diagnostic_msgs::msg::DiagnosticArray;
using diagnostic_msgs::msg::DiagnosticStatus;
using nav_msgs::msg::Odometry;
using TFMessage = tf2_msgs::msg::TFMessage;

Expand All @@ -60,15 +59,34 @@ class PerceptionOnlineEvaluatorNode : public rclcpp::Node
*/
void onObjects(const PredictedObjects::ConstSharedPtr objects_msg);

DiagnosticStatus generateDiagnosticStatus(
const std::string metric, const Accumulator<double> & metric_stat) const;
DiagnosticStatus generateDiagnosticStatus(
const std::string & metric, const double metric_value) const;
/**
* @brief Convert metric statistic to `tier4_metric_msgs::msg::Metric` and append to
* `tier4_metric_msgs::msg::MetricArray`.
*
* @param metric Metric name.
* @param metric_stat Metric statistic.
* @param metrics_msg Metrics value container.
*/
void toMetricMsg(
const std::string & metric, const Accumulator<double> & metric_stat,
tier4_metric_msgs::msg::MetricArray & metrics_msg) const;

/**
* @brief Convert metric value to `tier4_metric_msgs::msg::Metric` and append to
* `tier4_metric_msgs::msg::MetricArray
*
* @param metric Metric name.
* @param metric_stat Metric value.
* @param metrics_msg Metrics value container.
*/
void toMetricMsg(
const std::string & metric, const double metric_value,
tier4_metric_msgs::msg::MetricArray & metrics_msg) const;

private:
// Subscribers and publishers
rclcpp::Subscription<PredictedObjects>::SharedPtr objects_sub_;
rclcpp::Publisher<DiagnosticArray>::SharedPtr metrics_pub_;
rclcpp::Publisher<tier4_metric_msgs::msg::MetricArray>::SharedPtr metrics_pub_;
rclcpp::Publisher<MarkerArray>::SharedPtr pub_marker_;

// TF
Expand Down
2 changes: 1 addition & 1 deletion evaluator/perception_online_evaluator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
<depend>autoware_perception_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>diagnostic_msgs</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>glog</depend>
Expand All @@ -33,6 +32,7 @@
<depend>rclcpp_components</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tier4_metric_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_index_cpp</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode(

objects_sub_ = create_subscription<PredictedObjects>(
"~/input/objects", 1, std::bind(&PerceptionOnlineEvaluatorNode::onObjects, this, _1));
metrics_pub_ = create_publisher<DiagnosticArray>("~/metrics", 1);
metrics_pub_ = create_publisher<tier4_metric_msgs::msg::MetricArray>("~/metrics", 1);
pub_marker_ = create_publisher<MarkerArray>("~/markers", 10);

tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
Expand All @@ -65,7 +65,8 @@ PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode(

void PerceptionOnlineEvaluatorNode::publishMetrics()
{
DiagnosticArray metrics_msg;
// DiagnosticArray metrics_msg;
tier4_metric_msgs::msg::MetricArray metrics_msg;

// calculate metrics
for (const Metric & metric : parameters_->metrics) {
Expand All @@ -80,60 +81,54 @@ void PerceptionOnlineEvaluatorNode::publishMetrics()
for (const auto & [metric, value] : arg) {
if constexpr (std::is_same_v<T, MetricStatMap>) {
if (value.count() > 0) {
metrics_msg.status.emplace_back(generateDiagnosticStatus(metric, value));
toMetricMsg(metric, value, metrics_msg);
}
} else if constexpr (std::is_same_v<T, MetricValueMap>) {
metrics_msg.status.emplace_back(generateDiagnosticStatus(metric, value));
toMetricMsg(metric, value, metrics_msg);
}
}
},
metric_result.value());
}

// publish metrics
if (!metrics_msg.status.empty()) {
metrics_msg.header.stamp = now();
if (!metrics_msg.metric_array.empty()) {
metrics_msg.stamp = now();
metrics_pub_->publish(metrics_msg);
}
publishDebugMarker();
}

DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus(
const std::string metric, const Accumulator<double> & metric_stat) const
void PerceptionOnlineEvaluatorNode::toMetricMsg(
const std::string & metric, const Accumulator<double> & metric_stat,
tier4_metric_msgs::msg::MetricArray & metrics_msg) const
{
DiagnosticStatus status;

status.level = status.OK;
status.name = metric;

diagnostic_msgs::msg::KeyValue key_value;
key_value.key = "min";
key_value.value = std::to_string(metric_stat.min());
status.values.push_back(key_value);
key_value.key = "max";
key_value.value = std::to_string(metric_stat.max());
status.values.push_back(key_value);
key_value.key = "mean";
key_value.value = std::to_string(metric_stat.mean());
status.values.push_back(key_value);

return status;
// min value
metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build<tier4_metric_msgs::msg::Metric>()
.name(metric + "min")
ktro2828 marked this conversation as resolved.
Show resolved Hide resolved
.unit("m")
.value(std::to_string(metric_stat.min())));

// max value
metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build<tier4_metric_msgs::msg::Metric>()
.name(metric + "max")
.unit("m")
.value(std::to_string(metric_stat.max())));

// mean value
metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build<tier4_metric_msgs::msg::Metric>()
.name(metric + "mean")
.unit("m")
.value(std::to_string(metric_stat.mean())));
}

DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus(
const std::string & metric, const double value) const
void PerceptionOnlineEvaluatorNode::toMetricMsg(
const std::string & metric, const double metric_value,
tier4_metric_msgs::msg::MetricArray & metrics_msg) const
{
DiagnosticStatus status;

status.level = status.OK;
status.name = metric;

diagnostic_msgs::msg::KeyValue key_value;
key_value.key = "metric_value";
key_value.value = std::to_string(value);
status.values.push_back(key_value);

return status;
metrics_msg.metric_array.emplace_back(
tier4_metric_msgs::build<tier4_metric_msgs::msg::Metric>().name(metric).unit("m").value(
std::to_string(metric_value)));
}

void PerceptionOnlineEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg)
Expand Down
Loading