Skip to content

Commit 1adb6a9

Browse files
committed
chore: Add object filtering to data association
1 parent 5de95b0 commit 1adb6a9

File tree

3 files changed

+34
-7
lines changed

3 files changed

+34
-7
lines changed

perception/multi_object_tracker/include/multi_object_tracker/data_association/data_association.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@ class DataAssociation
5454
void assign(
5555
const Eigen::MatrixXd & src, std::unordered_map<int, int> & direct_assignment,
5656
std::unordered_map<int, int> & reverse_assignment);
57+
void objectFilter(autoware_auto_perception_msgs::msg::DetectedObjects & measurements) const;
5758
Eigen::MatrixXd calcScoreMatrix(
5859
const autoware_auto_perception_msgs::msg::DetectedObjects & measurements,
5960
const std::list<std::shared_ptr<Tracker>> & trackers);

perception/multi_object_tracker/src/data_association/data_association.cpp

+31-7
Original file line numberDiff line numberDiff line change
@@ -146,6 +146,37 @@ void DataAssociation::assign(
146146
}
147147
}
148148

149+
void DataAssociation::objectFilter(
150+
autoware_auto_perception_msgs::msg::DetectedObjects & measurements) const
151+
{
152+
using Label = autoware_auto_perception_msgs::msg::ObjectClassification;
153+
154+
for (auto & measurement_object : measurements.objects) {
155+
auto & obj_class_list = measurement_object.classification;
156+
const std::uint8_t measurement_label =
157+
object_recognition_utils::getHighestProbLabel(obj_class_list);
158+
bool passed_gate = true;
159+
const double max_area = max_area_matrix_(measurement_label, measurement_label);
160+
const double min_area = min_area_matrix_(measurement_label, measurement_label);
161+
const double area = tier4_autoware_utils::getArea(measurement_object.shape);
162+
if (area < min_area || max_area < area) passed_gate = false;
163+
164+
//
165+
if (!passed_gate) {
166+
// change top-rate label to unknown, step back the existing labels
167+
constexpr float RATE_REDUCED = 0.3f;
168+
constexpr float RATE_OVERWRITE = 0.7f;
169+
for (auto & obj_class : obj_class_list) {
170+
obj_class.probability *= RATE_REDUCED;
171+
}
172+
Label new_obj_class;
173+
new_obj_class.label = Label::UNKNOWN;
174+
new_obj_class.probability = RATE_OVERWRITE;
175+
obj_class_list.emplace_back(new_obj_class);
176+
}
177+
}
178+
}
179+
149180
Eigen::MatrixXd DataAssociation::calcScoreMatrix(
150181
const autoware_auto_perception_msgs::msg::DetectedObjects & measurements,
151182
const std::list<std::shared_ptr<Tracker>> & trackers)
@@ -179,13 +210,6 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
179210
if (passed_gate) {
180211
if (max_dist < dist) passed_gate = false;
181212
}
182-
// area gate
183-
if (passed_gate) {
184-
const double max_area = max_area_matrix_(tracker_label, measurement_label);
185-
const double min_area = min_area_matrix_(tracker_label, measurement_label);
186-
const double area = tier4_autoware_utils::getArea(measurement_object.shape);
187-
if (area < min_area || max_area < area) passed_gate = false;
188-
}
189213
// angle gate
190214
if (passed_gate) {
191215
const double max_rad = max_rad_matrix_(tracker_label, measurement_label);

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -264,6 +264,8 @@ void MultiObjectTracker::onMeasurement(
264264
(*itr)->predict(measurement_time);
265265
}
266266

267+
data_association_->objectFilter(transformed_objects);
268+
267269
/* global nearest neighbor */
268270
std::unordered_map<int, int> direct_assignment, reverse_assignment;
269271
Eigen::MatrixXd score_matrix = data_association_->calcScoreMatrix(

0 commit comments

Comments
 (0)