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

feat(multi_object_tracker): add object filtering to data association #1605

Closed
Show file tree
Hide file tree
Changes from all commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ class DataAssociation
void assign(
const Eigen::MatrixXd & src, std::unordered_map<int, int> & direct_assignment,
std::unordered_map<int, int> & reverse_assignment);
void objectFilter(autoware_auto_perception_msgs::msg::DetectedObjects & measurements) const;
Eigen::MatrixXd calcScoreMatrix(
const autoware_auto_perception_msgs::msg::DetectedObjects & measurements,
const std::list<std::shared_ptr<Tracker>> & trackers);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -146,6 +146,37 @@ void DataAssociation::assign(
}
}

void DataAssociation::objectFilter(
autoware_auto_perception_msgs::msg::DetectedObjects & measurements) const
{
using Label = autoware_auto_perception_msgs::msg::ObjectClassification;

for (auto & measurement_object : measurements.objects) {
auto & obj_class_list = measurement_object.classification;
const std::uint8_t measurement_label =
object_recognition_utils::getHighestProbLabel(obj_class_list);
bool passed_gate = true;
const double max_area = max_area_matrix_(measurement_label, measurement_label);
const double min_area = min_area_matrix_(measurement_label, measurement_label);
const double area = tier4_autoware_utils::getArea(measurement_object.shape);
if (area < min_area || max_area < area) passed_gate = false;

//
if (!passed_gate) {
// change top-rate label to unknown, step back the existing labels
constexpr float RATE_REDUCED = 0.3f;
constexpr float RATE_OVERWRITE = 0.7f;
for (auto & obj_class : obj_class_list) {
obj_class.probability *= RATE_REDUCED;
}
Label new_obj_class;
new_obj_class.label = Label::UNKNOWN;
new_obj_class.probability = RATE_OVERWRITE;
obj_class_list.emplace_back(new_obj_class);
}
}
}

Eigen::MatrixXd DataAssociation::calcScoreMatrix(
const autoware_auto_perception_msgs::msg::DetectedObjects & measurements,
const std::list<std::shared_ptr<Tracker>> & trackers)
Expand Down Expand Up @@ -179,13 +210,6 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
if (passed_gate) {
if (max_dist < dist) passed_gate = false;
}
// area gate
if (passed_gate) {
const double max_area = max_area_matrix_(tracker_label, measurement_label);
const double min_area = min_area_matrix_(tracker_label, measurement_label);
const double area = tier4_autoware_utils::getArea(measurement_object.shape);
if (area < min_area || max_area < area) passed_gate = false;
}
// angle gate
if (passed_gate) {
const double max_rad = max_rad_matrix_(tracker_label, measurement_label);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -264,6 +264,8 @@ void MultiObjectTracker::onMeasurement(
(*itr)->predict(measurement_time);
}

data_association_->objectFilter(transformed_objects);

/* global nearest neighbor */
std::unordered_map<int, int> direct_assignment, reverse_assignment;
Eigen::MatrixXd score_matrix = data_association_->calcScoreMatrix(
Expand Down
Loading