@@ -38,11 +38,6 @@ std::optional<MetricStatMap> MetricsCalculator::calculate(const Metric & metric)
38
38
}
39
39
const auto target_objects = getObjectsByStamp (target_stamp);
40
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
- }
45
-
46
41
switch (metric) {
47
42
case Metric::lateral_deviation:
48
43
return calcLateralDeviationMetrics (class_objects_map);
@@ -166,7 +161,7 @@ MetricStatMap MetricsCalculator::calcLateralDeviationMetrics(
166
161
const ClassObjectsMap & class_objects_map) const
167
162
{
168
163
MetricStatMap metric_stat_map{};
169
- for (const auto [label, objects] : class_objects_map) {
164
+ for (const auto & [label, objects] : class_objects_map) {
170
165
Stat<double > stat{};
171
166
const auto stamp = rclcpp::Time (objects.header .stamp );
172
167
for (const auto & object : objects.objects ) {
@@ -190,7 +185,7 @@ MetricStatMap MetricsCalculator::calcYawDeviationMetrics(
190
185
const ClassObjectsMap & class_objects_map) const
191
186
{
192
187
MetricStatMap metric_stat_map{};
193
- for (const auto [label, objects] : class_objects_map) {
188
+ for (const auto & [label, objects] : class_objects_map) {
194
189
Stat<double > stat{};
195
190
const auto stamp = rclcpp::Time (objects.header .stamp );
196
191
for (const auto & object : objects.objects ) {
@@ -216,7 +211,7 @@ MetricStatMap MetricsCalculator::calcPredictedPathDeviationMetrics(
216
211
const auto time_horizons = parameters_->prediction_time_horizons ;
217
212
218
213
MetricStatMap metric_stat_map{};
219
- for (const auto [label, objects] : class_objects_map) {
214
+ for (const auto & [label, objects] : class_objects_map) {
220
215
for (const double time_horizon : time_horizons) {
221
216
const auto stat = calcPredictedPathDeviationMetrics (objects, time_horizon);
222
217
std::ostringstream stream;
0 commit comments