Skip to content

Commit 40f3796

Browse files
committed
feat(perception_online_evaluator): publish metrics of each object class
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 7ef61a9 commit 40f3796

File tree

6 files changed

+167
-73
lines changed

6 files changed

+167
-73
lines changed

evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include "perception_online_evaluator/metrics/metric.hpp"
2020
#include "perception_online_evaluator/parameters.hpp"
2121
#include "perception_online_evaluator/stat.hpp"
22+
#include "perception_online_evaluator/utils/objects_filtering.hpp"
2223

2324
#include <rclcpp/time.hpp>
2425

@@ -118,9 +119,9 @@ class MetricsCalculator
118119
void deleteOldObjects(const rclcpp::Time stamp);
119120

120121
// Calculate metrics
121-
MetricStatMap calcLateralDeviationMetrics(const PredictedObjects & objects) const;
122-
MetricStatMap calcYawDeviationMetrics(const PredictedObjects & objects) const;
123-
MetricStatMap calcPredictedPathDeviationMetrics(const PredictedObjects & objects) const;
122+
MetricStatMap calcLateralDeviationMetrics(const ClassObjectsMap & class_objects_map) const;
123+
MetricStatMap calcYawDeviationMetrics(const ClassObjectsMap & class_objects_map) const;
124+
MetricStatMap calcPredictedPathDeviationMetrics(const ClassObjectsMap & class_objects_map) const;
124125
Stat<double> calcPredictedPathDeviationMetrics(
125126
const PredictedObjects & objects, const double time_horizon) const;
126127

evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/objects_filtering.hpp

+10
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,8 @@ using autoware_auto_perception_msgs::msg::ObjectClassification;
3737
using autoware_auto_perception_msgs::msg::PredictedObject;
3838
using autoware_auto_perception_msgs::msg::PredictedObjects;
3939

40+
using ClassObjectsMap = std::unordered_map<uint8_t, PredictedObjects>;
41+
4042
std::uint8_t getHighestProbLabel(const std::vector<ObjectClassification> & classification);
4143

4244
/**
@@ -105,6 +107,14 @@ void filterObjects(PredictedObjects & objects, Func filter)
105107
filterObjects(objects, removed_objects, filter);
106108
}
107109

110+
/**
111+
* @brief Separates the provided objects based on their classification.
112+
*
113+
* @param objects The predicted objects to be separated.
114+
* @return A map of objects separated by their classification.
115+
*/
116+
ClassObjectsMap separateObjectsByClass(const PredictedObjects & objects);
117+
108118
/**
109119
* @brief Filters the provided objects based on their classification.
110120
*

evaluator/perception_online_evaluator/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
<depend>libgoogle-glog-dev</depend>
2525
<depend>motion_utils</depend>
2626
<depend>nav_msgs</depend>
27+
<depend>object_recognition_utils</depend>
2728
<depend>pluginlib</depend>
2829
<depend>rclcpp</depend>
2930
<depend>rclcpp_components</depend>

evaluator/perception_online_evaluator/src/metrics_calculator.cpp

+58-46
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,15 @@
1515
#include "perception_online_evaluator/metrics_calculator.hpp"
1616

1717
#include "motion_utils/trajectory/trajectory.hpp"
18-
#include "perception_online_evaluator/utils/objects_filtering.hpp"
18+
#include "object_recognition_utils/object_recognition_utils.hpp"
1919
#include "tier4_autoware_utils/geometry/geometry.hpp"
2020

2121
#include <tier4_autoware_utils/ros/uuid_helper.hpp>
2222

2323
namespace perception_diagnostics
2424
{
25+
using object_recognition_utils::convertLabelToString;
26+
2527
std::optional<MetricStatMap> MetricsCalculator::calculate(const Metric & metric) const
2628
{
2729
if (object_map_.empty()) {
@@ -35,14 +37,19 @@ std::optional<MetricStatMap> MetricsCalculator::calculate(const Metric & metric)
3537
return {};
3638
}
3739
const auto target_objects = getObjectsByStamp(target_stamp);
40+
const ClassObjectsMap class_objects_map = separateObjectsByClass(target_objects);
41+
42+
// print class and size
43+
for (const auto [label, objects] : class_objects_map) {
44+
}
3845

3946
switch (metric) {
4047
case Metric::lateral_deviation:
41-
return calcLateralDeviationMetrics(target_objects);
48+
return calcLateralDeviationMetrics(class_objects_map);
4249
case Metric::yaw_deviation:
43-
return calcYawDeviationMetrics(target_objects);
50+
return calcYawDeviationMetrics(class_objects_map);
4451
case Metric::predicted_path_deviation:
45-
return calcPredictedPathDeviationMetrics(target_objects);
52+
return calcPredictedPathDeviationMetrics(class_objects_map);
4653
default:
4754
return {};
4855
}
@@ -155,65 +162,70 @@ PredictedObjects MetricsCalculator::getObjectsByStamp(const rclcpp::Time stamp)
155162
return objects;
156163
}
157164

158-
MetricStatMap MetricsCalculator::calcLateralDeviationMetrics(const PredictedObjects & objects) const
165+
MetricStatMap MetricsCalculator::calcLateralDeviationMetrics(
166+
const ClassObjectsMap & class_objects_map) const
159167
{
160-
Stat<double> stat{};
161-
const auto stamp = rclcpp::Time(objects.header.stamp);
162-
163-
for (const auto & object : objects.objects) {
164-
const auto uuid = tier4_autoware_utils::toHexString(object.object_id);
165-
if (!hasPassedTime(uuid, stamp)) {
166-
continue;
167-
}
168-
const auto object_pose = object.kinematics.initial_pose_with_covariance.pose;
169-
const auto history_path = history_path_map_.at(uuid).second;
170-
if (history_path.empty()) {
171-
continue;
168+
MetricStatMap metric_stat_map{};
169+
for (const auto [label, objects] : class_objects_map) {
170+
Stat<double> stat{};
171+
const auto stamp = rclcpp::Time(objects.header.stamp);
172+
for (const auto & object : objects.objects) {
173+
const auto uuid = tier4_autoware_utils::toHexString(object.object_id);
174+
if (!hasPassedTime(uuid, stamp)) {
175+
continue;
176+
}
177+
const auto object_pose = object.kinematics.initial_pose_with_covariance.pose;
178+
const auto history_path = history_path_map_.at(uuid).second;
179+
if (history_path.empty()) {
180+
continue;
181+
}
182+
stat.add(metrics::calcLateralDeviation(history_path, object_pose));
172183
}
173-
stat.add(metrics::calcLateralDeviation(history_path, object_pose));
184+
metric_stat_map["lateral_deviation_" + convertLabelToString(label)] = stat;
174185
}
175-
176-
MetricStatMap metric_stat_map;
177-
metric_stat_map["lateral_deviation"] = stat;
178186
return metric_stat_map;
179187
}
180188

181-
MetricStatMap MetricsCalculator::calcYawDeviationMetrics(const PredictedObjects & objects) const
189+
MetricStatMap MetricsCalculator::calcYawDeviationMetrics(
190+
const ClassObjectsMap & class_objects_map) const
182191
{
183-
Stat<double> stat{};
184-
const auto stamp = rclcpp::Time(objects.header.stamp);
185-
for (const auto & object : objects.objects) {
186-
const auto uuid = tier4_autoware_utils::toHexString(object.object_id);
187-
if (!hasPassedTime(uuid, stamp)) {
188-
continue;
189-
}
190-
const auto object_pose = object.kinematics.initial_pose_with_covariance.pose;
191-
const auto history_path = history_path_map_.at(uuid).second;
192-
if (history_path.empty()) {
193-
continue;
192+
MetricStatMap metric_stat_map{};
193+
for (const auto [label, objects] : class_objects_map) {
194+
Stat<double> stat{};
195+
const auto stamp = rclcpp::Time(objects.header.stamp);
196+
for (const auto & object : objects.objects) {
197+
const auto uuid = tier4_autoware_utils::toHexString(object.object_id);
198+
if (!hasPassedTime(uuid, stamp)) {
199+
continue;
200+
}
201+
const auto object_pose = object.kinematics.initial_pose_with_covariance.pose;
202+
const auto history_path = history_path_map_.at(uuid).second;
203+
if (history_path.empty()) {
204+
continue;
205+
}
206+
stat.add(metrics::calcYawDeviation(history_path, object_pose));
194207
}
195-
stat.add(metrics::calcYawDeviation(history_path, object_pose));
208+
metric_stat_map["yaw_deviation_" + convertLabelToString(label)] = stat;
196209
}
197-
198-
MetricStatMap metric_stat_map;
199-
metric_stat_map["yaw_deviation"] = stat;
200210
return metric_stat_map;
201211
}
202212

203213
MetricStatMap MetricsCalculator::calcPredictedPathDeviationMetrics(
204-
const PredictedObjects & objects) const
214+
const ClassObjectsMap & class_objects_map) const
205215
{
206216
const auto time_horizons = parameters_->prediction_time_horizons;
207217

208-
MetricStatMap metric_stat_map;
209-
for (const double time_horizon : time_horizons) {
210-
const auto stat = calcPredictedPathDeviationMetrics(objects, time_horizon);
211-
std::ostringstream stream;
212-
stream << std::fixed << std::setprecision(2) << time_horizon;
213-
std::string time_horizon_str = stream.str();
214-
metric_stat_map["predicted_path_deviation_" + time_horizon_str] = stat;
218+
MetricStatMap metric_stat_map{};
219+
for (const auto [label, objects] : class_objects_map) {
220+
for (const double time_horizon : time_horizons) {
221+
const auto stat = calcPredictedPathDeviationMetrics(objects, time_horizon);
222+
std::ostringstream stream;
223+
stream << std::fixed << std::setprecision(2) << time_horizon;
224+
std::string time_horizon_str = stream.str();
225+
metric_stat_map
226+
["predicted_path_deviation_" + convertLabelToString(label) + "_" + time_horizon_str] = stat;
227+
}
215228
}
216-
217229
return metric_stat_map;
218230
}
219231

evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp

+11
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,17 @@ bool isTargetObjectType(
8383
(t == ObjectClassification::PEDESTRIAN && target_object_types.check_pedestrian));
8484
}
8585

86+
ClassObjectsMap separateObjectsByClass(const PredictedObjects & objects)
87+
{
88+
ClassObjectsMap separated_objects;
89+
for (const auto & object : objects.objects) {
90+
const auto label = getHighestProbLabel(object.classification);
91+
separated_objects[label].objects.push_back(object);
92+
separated_objects[label].header = objects.header;
93+
}
94+
return separated_objects;
95+
}
96+
8697
void filterObjectsByClass(
8798
PredictedObjects & objects, const ObjectTypesToCheck & target_object_types)
8899
{

0 commit comments

Comments
 (0)