Skip to content

Commit b7f2079

Browse files
authored
feat(perception_online_evaluator): add yaw rate metrics for stopped object (#6667)
* feat(perception_online_evaluator): add yaw rate metrics for stopped object Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> add Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> add test * feat: add stopped vel parameter Signed-off-by: kosuke55 <kosuke.tnp@gmail.com> --------- Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 3683131 commit b7f2079

10 files changed

+302
-12
lines changed

evaluator/perception_online_evaluator/README.md

+1
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@ This module allows for the evaluation of how accurately perception results are g
2727
| `selected_metrics` | List | Metrics to be evaluated, such as lateral deviation, yaw deviation, and predicted path deviation. |
2828
| `smoothing_window_size` | Integer | Determines the window size for smoothing path, should be an odd number. |
2929
| `prediction_time_horizons` | list[double] | Time horizons for prediction evaluation in seconds. |
30+
| `stopped_velocity_threshold` | double | threshold velocity to check if vehicle is stopped |
3031
| `target_object.*.check_deviation` | bool | Whether to check deviation for specific object types (car, truck, etc.). |
3132
| `debug_marker.*` | bool | Debugging parameters for marker visualization (history path, predicted path, etc.). |
3233

evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@ enum class Metric {
3131
lateral_deviation,
3232
yaw_deviation,
3333
predicted_path_deviation,
34+
yaw_rate,
3435
SIZE,
3536
};
3637

@@ -39,18 +40,21 @@ using MetricStatMap = std::unordered_map<std::string, Stat<double>>;
3940
static const std::unordered_map<std::string, Metric> str_to_metric = {
4041
{"lateral_deviation", Metric::lateral_deviation},
4142
{"yaw_deviation", Metric::yaw_deviation},
42-
{"predicted_path_deviation", Metric::predicted_path_deviation}};
43+
{"predicted_path_deviation", Metric::predicted_path_deviation},
44+
{"yaw_rate", Metric::yaw_rate}};
4345

4446
static const std::unordered_map<Metric, std::string> metric_to_str = {
4547
{Metric::lateral_deviation, "lateral_deviation"},
4648
{Metric::yaw_deviation, "yaw_deviation"},
47-
{Metric::predicted_path_deviation, "predicted_path_deviation"}};
49+
{Metric::predicted_path_deviation, "predicted_path_deviation"},
50+
{Metric::yaw_rate, "yaw_rate"}};
4851

4952
// Metrics descriptions
5053
static const std::unordered_map<Metric, std::string> metric_descriptions = {
5154
{Metric::lateral_deviation, "Lateral_deviation[m]"},
5255
{Metric::yaw_deviation, "Yaw_deviation[rad]"},
53-
{Metric::predicted_path_deviation, "Predicted_path_deviation[m]"}};
56+
{Metric::predicted_path_deviation, "Predicted_path_deviation[m]"},
57+
{Metric::yaw_rate, "Yaw_rate[rad/s]"}};
5458

5559
namespace details
5660
{

evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp

+10-1
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,10 @@ using ObjectDataMap = std::unordered_map<std::string, ObjectData>;
7272
using HistoryPathMap =
7373
std::unordered_map<std::string, std::pair<std::vector<Pose>, std::vector<Pose>>>;
7474

75+
using StampObjectMap = std::map<rclcpp::Time, PredictedObject>;
76+
using StampObjectMapIterator = std::map<rclcpp::Time, PredictedObject>::const_iterator;
77+
using ObjectMap = std::unordered_map<std::string, StampObjectMap>;
78+
7579
class MetricsCalculator
7680
{
7781
public:
@@ -98,7 +102,7 @@ class MetricsCalculator
98102
std::shared_ptr<Parameters> parameters_;
99103

100104
// Store predicted objects information and calculation results
101-
std::unordered_map<std::string, std::map<rclcpp::Time, PredictedObject>> object_map_;
105+
ObjectMap object_map_;
102106
HistoryPathMap history_path_map_;
103107

104108
rclcpp::Time current_stamp_;
@@ -124,15 +128,20 @@ class MetricsCalculator
124128
MetricStatMap calcPredictedPathDeviationMetrics(const ClassObjectsMap & class_objects_map) const;
125129
Stat<double> calcPredictedPathDeviationMetrics(
126130
const PredictedObjects & objects, const double time_horizon) const;
131+
MetricStatMap calcYawRateMetrics(const ClassObjectsMap & class_objects_map) const;
127132

128133
bool hasPassedTime(const rclcpp::Time stamp) const;
129134
bool hasPassedTime(const std::string uuid, const rclcpp::Time stamp) const;
130135
double getTimeDelay() const;
131136

132137
// Extract object
133138
rclcpp::Time getClosestStamp(const rclcpp::Time stamp) const;
139+
std::optional<StampObjectMapIterator> getClosestObjectIterator(
140+
const std::string & uuid, const rclcpp::Time & stamp) const;
134141
std::optional<PredictedObject> getObjectByStamp(
135142
const std::string uuid, const rclcpp::Time stamp) const;
143+
std::optional<std::pair<rclcpp::Time, PredictedObject>> getPreviousObjectByStamp(
144+
const std::string uuid, const rclcpp::Time stamp) const;
136145
PredictedObjects getObjectsByStamp(const rclcpp::Time stamp) const;
137146

138147
}; // class MetricsCalculator

evaluator/perception_online_evaluator/include/perception_online_evaluator/parameters.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,7 @@ struct Parameters
4848
std::vector<Metric> metrics;
4949
size_t smoothing_window_size{0};
5050
std::vector<double> prediction_time_horizons;
51+
double stopped_velocity_threshold{0.0};
5152
DebugMarkerParameter debug_marker_parameters;
5253
// parameters depend on object class
5354
std::unordered_map<uint8_t, ObjectParameter> object_parameters;

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

+37
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include <autoware_auto_perception_msgs/msg/predicted_object.hpp>
2222
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
2323

24+
#include <cmath>
2425
#include <memory>
2526
#include <unordered_map>
2627
#include <utility>
@@ -39,6 +40,9 @@ using autoware_auto_perception_msgs::msg::PredictedObjects;
3940

4041
using ClassObjectsMap = std::unordered_map<uint8_t, PredictedObjects>;
4142

43+
bool velocity_filter(
44+
const PredictedObject & object, double velocity_threshold, double max_velocity);
45+
4246
std::uint8_t getHighestProbLabel(const std::vector<ObjectClassification> & classification);
4347

4448
/**
@@ -133,6 +137,39 @@ void filterObjectsByClass(
133137
void filterDeviationCheckObjects(
134138
PredictedObjects & objects, const std::unordered_map<uint8_t, ObjectParameter> & params);
135139

140+
/**
141+
* @brief Filters objects based on their velocity.
142+
*
143+
* Depending on the remove_above_threshold parameter, this function either removes objects with
144+
* velocities above the given threshold or only keeps those objects. It uses the helper function
145+
* filterObjectsByVelocity() to do the actual filtering.
146+
*
147+
* @param objects The objects to be filtered.
148+
* @param velocity_threshold The velocity threshold for the filtering.
149+
* @param remove_above_threshold If true, objects with velocities above the threshold are removed.
150+
* If false, only objects with velocities above the threshold are
151+
* kept.
152+
* @return A new collection of objects that have been filtered according to the rules.
153+
*/
154+
PredictedObjects filterObjectsByVelocity(
155+
const PredictedObjects & objects, const double velocity_threshold,
156+
const bool remove_above_threshold = true);
157+
158+
/**
159+
* @brief Helper function to filter objects based on their velocity.
160+
*
161+
* This function iterates over all objects and calculates their velocity norm. If the velocity norm
162+
* is within the velocity_threshold and max_velocity range, the object is added to a new collection.
163+
* This new collection is then returned.
164+
*
165+
* @param objects The objects to be filtered.
166+
* @param velocity_threshold The minimum velocity for an object to be included in the output.
167+
* @param max_velocity The maximum velocity for an object to be included in the output.
168+
* @return A new collection of objects that have been filtered according to the rules.
169+
*/
170+
PredictedObjects filterObjectsByVelocity(
171+
const PredictedObjects & objects, double velocity_threshold, double max_velocity);
172+
136173
} // namespace perception_diagnostics
137174

138175
#endif // PERCEPTION_ONLINE_EVALUATOR__UTILS__OBJECTS_FILTERING_HPP_

evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml

+3
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,15 @@
44
- lateral_deviation
55
- yaw_deviation
66
- predicted_path_deviation
7+
- yaw_rate
78

89
# this should be an odd number, because it includes the target point
910
smoothing_window_size: 11
1011

1112
prediction_time_horizons: [1.0, 2.0, 3.0, 5.0]
1213

14+
stopped_velocity_threshold: 0.3
15+
1316
target_object:
1417
car:
1518
check_deviation: true

evaluator/perception_online_evaluator/src/metrics_calculator.cpp

+83-8
Original file line numberDiff line numberDiff line change
@@ -36,15 +36,23 @@ std::optional<MetricStatMap> MetricsCalculator::calculate(const Metric & metric)
3636
if (!hasPassedTime(target_stamp)) {
3737
return {};
3838
}
39-
const auto target_objects = getObjectsByStamp(target_stamp);
40-
const ClassObjectsMap class_objects_map = separateObjectsByClass(target_objects);
39+
const auto target_stamp_objects = getObjectsByStamp(target_stamp);
40+
const auto class_objects_map = separateObjectsByClass(target_stamp_objects);
41+
42+
// filter stopped objects
43+
const auto stopped_objects =
44+
filterObjectsByVelocity(target_stamp_objects, parameters_->stopped_velocity_threshold);
45+
const auto class_stopped_objects_map = separateObjectsByClass(stopped_objects);
46+
4147
switch (metric) {
4248
case Metric::lateral_deviation:
4349
return calcLateralDeviationMetrics(class_objects_map);
4450
case Metric::yaw_deviation:
4551
return calcYawDeviationMetrics(class_objects_map);
4652
case Metric::predicted_path_deviation:
4753
return calcPredictedPathDeviationMetrics(class_objects_map);
54+
case Metric::yaw_rate:
55+
return calcYawRateMetrics(class_stopped_objects_map);
4856
default:
4957
return {};
5058
}
@@ -124,16 +132,46 @@ rclcpp::Time MetricsCalculator::getClosestStamp(const rclcpp::Time stamp) const
124132
return closest_stamp;
125133
}
126134

127-
std::optional<PredictedObject> MetricsCalculator::getObjectByStamp(
128-
const std::string uuid, const rclcpp::Time stamp) const
135+
std::optional<StampObjectMapIterator> MetricsCalculator::getClosestObjectIterator(
136+
const std::string & uuid, const rclcpp::Time & stamp) const
129137
{
130138
const auto closest_stamp = getClosestStamp(stamp);
131-
auto it = std::lower_bound(
139+
const auto it = std::lower_bound(
132140
object_map_.at(uuid).begin(), object_map_.at(uuid).end(), closest_stamp,
133141
[](const auto & pair, const rclcpp::Time & val) { return pair.first < val; });
134142

135-
if (it != object_map_.at(uuid).end() && it->first == closest_stamp) {
136-
return it->second;
143+
return it != object_map_.at(uuid).end() ? std::optional<StampObjectMapIterator>(it)
144+
: std::nullopt;
145+
}
146+
147+
std::optional<PredictedObject> MetricsCalculator::getObjectByStamp(
148+
const std::string uuid, const rclcpp::Time stamp) const
149+
{
150+
const auto obj_it_opt = getClosestObjectIterator(uuid, stamp);
151+
if (obj_it_opt.has_value()) {
152+
const auto it = obj_it_opt.value();
153+
if (it->first == getClosestStamp(stamp)) {
154+
return it->second;
155+
}
156+
}
157+
return std::nullopt;
158+
}
159+
160+
std::optional<std::pair<rclcpp::Time, PredictedObject>> MetricsCalculator::getPreviousObjectByStamp(
161+
const std::string uuid, const rclcpp::Time stamp) const
162+
{
163+
const auto obj_it_opt = getClosestObjectIterator(uuid, stamp);
164+
if (obj_it_opt.has_value()) {
165+
auto it = obj_it_opt.value();
166+
if (it != object_map_.at(uuid).begin()) {
167+
// If it is exactly the closest stamp, move one back to get the previous
168+
if (it->first == getClosestStamp(stamp)) {
169+
--it;
170+
} else {
171+
// If it is not the closest stamp, it already points to the previous one due to lower_bound
172+
}
173+
return std::make_pair(it->first, it->second);
174+
}
137175
}
138176
return std::nullopt;
139177
}
@@ -313,9 +351,46 @@ Stat<double> MetricsCalculator::calcPredictedPathDeviationMetrics(
313351
return stat;
314352
}
315353

354+
MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & class_objects_map) const
355+
{
356+
// calculate yaw rate for each object
357+
358+
MetricStatMap metric_stat_map{};
359+
360+
for (const auto & [label, objects] : class_objects_map) {
361+
Stat<double> stat{};
362+
const auto stamp = rclcpp::Time(objects.header.stamp);
363+
364+
for (const auto & object : objects.objects) {
365+
const auto uuid = tier4_autoware_utils::toHexString(object.object_id);
366+
if (!hasPassedTime(uuid, stamp)) {
367+
continue;
368+
}
369+
const auto previous_object_with_stamp_opt = getPreviousObjectByStamp(uuid, stamp);
370+
if (!previous_object_with_stamp_opt.has_value()) {
371+
continue;
372+
}
373+
const auto [previous_stamp, previous_object] = previous_object_with_stamp_opt.value();
374+
375+
const auto time_diff = (stamp - previous_stamp).seconds();
376+
if (time_diff < 0.01) {
377+
continue;
378+
}
379+
const auto current_yaw =
380+
tf2::getYaw(object.kinematics.initial_pose_with_covariance.pose.orientation);
381+
const auto previous_yaw =
382+
tf2::getYaw(previous_object.kinematics.initial_pose_with_covariance.pose.orientation);
383+
const auto yaw_rate =
384+
std::abs(tier4_autoware_utils::normalizeRadian(current_yaw - previous_yaw) / time_diff);
385+
stat.add(yaw_rate);
386+
}
387+
metric_stat_map["yaw_rate_" + convertLabelToString(label)] = stat;
388+
}
389+
return metric_stat_map;
390+
}
391+
316392
void MetricsCalculator::setPredictedObjects(const PredictedObjects & objects)
317393
{
318-
// using TimeStamp = builtin_interfaces::msg::Time;
319394
current_stamp_ = objects.header.stamp;
320395

321396
// store objects to check deviation

evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -280,6 +280,8 @@ void PerceptionOnlineEvaluatorNode::initParameter()
280280
p->smoothing_window_size = getOrDeclareParameter<int>(*this, "smoothing_window_size");
281281
p->prediction_time_horizons =
282282
getOrDeclareParameter<std::vector<double>>(*this, "prediction_time_horizons");
283+
p->stopped_velocity_threshold =
284+
getOrDeclareParameter<double>(*this, "stopped_velocity_threshold");
283285

284286
// set metrics
285287
const auto selected_metrics =

evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp

+32
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,17 @@
1616

1717
namespace perception_diagnostics
1818
{
19+
namespace filter
20+
{
21+
bool velocity_filter(const PredictedObject & object, double velocity_threshold, double max_velocity)
22+
{
23+
const auto v_norm = std::hypot(
24+
object.kinematics.initial_twist_with_covariance.twist.linear.x,
25+
object.kinematics.initial_twist_with_covariance.twist.linear.y);
26+
return (velocity_threshold < v_norm && v_norm < max_velocity);
27+
}
28+
} // namespace filter
29+
1930
ObjectTypesToCheck getDeviationCheckObjectTypes(
2031
const std::unordered_map<uint8_t, ObjectParameter> & params)
2132
{
@@ -111,4 +122,25 @@ void filterDeviationCheckObjects(
111122
filterObjectsByClass(objects, object_types);
112123
}
113124

125+
PredictedObjects filterObjectsByVelocity(
126+
const PredictedObjects & objects, const double velocity_threshold,
127+
const bool remove_above_threshold)
128+
{
129+
if (remove_above_threshold) {
130+
return filterObjectsByVelocity(objects, -velocity_threshold, velocity_threshold);
131+
}
132+
return filterObjectsByVelocity(objects, velocity_threshold, std::numeric_limits<double>::max());
133+
}
134+
135+
PredictedObjects filterObjectsByVelocity(
136+
const PredictedObjects & objects, double velocity_threshold, double max_velocity)
137+
{
138+
const auto filter = [&](const auto & object) {
139+
return filter::velocity_filter(object, velocity_threshold, max_velocity);
140+
};
141+
142+
auto filtered = objects;
143+
filterObjects(filtered, filter);
144+
return filtered;
145+
}
114146
} // namespace perception_diagnostics

0 commit comments

Comments
 (0)