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 class filtering in tracking process #6607

Merged
Merged
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 @@ -42,6 +42,8 @@ class Tracker
{
classification_ = classification;
}
void updateClassification(
const std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> & classification);

private:
unique_identifier_msgs::msg::UUID uuid_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ bool MultipleVehicleTracker::measure(
big_vehicle_tracker_.measure(object, time, self_transform);
normal_vehicle_tracker_.measure(object, time, self_transform);
if (object_recognition_utils::getHighestProbLabel(object.classification) != Label::UNKNOWN)
setClassification(object.classification);
updateClassification(object.classification);
return true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ bool PedestrianAndBicycleTracker::measure(
pedestrian_tracker_.measure(object, time, self_transform);
bicycle_tracker_.measure(object, time, self_transform);
if (object_recognition_utils::getHighestProbLabel(object.classification) != Label::UNKNOWN)
setClassification(object.classification);
updateClassification(object.classification);
return true;
}

Expand Down
61 changes: 61 additions & 0 deletions perception/multi_object_tracker/src/tracker/model/tracker_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,67 @@ bool Tracker::updateWithoutMeasurement()
return true;
}

void Tracker::updateClassification(
const std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> & classification)
{
// classification algorithm:
// 0. Normalize the input classification
// 1-1. Update the matched classification probability with a gain (ratio of 0.05)
// 1-2. If the label is not found, add it to the classification list
// 2. Remove the class with probability < remove_threshold (0.001)
// 3. Normalize tracking classification

// Parameters
// if the remove_threshold is too high (compare to the gain), the classification will be removed
// immediately
const double gain = 0.05;
constexpr double remove_threshold = 0.001;

// Normalization function
auto normalizeProbabilities =
[](std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> & classification) {
double sum = 0.0;
for (const auto & class_ : classification) {
sum += class_.probability;
}
for (auto & class_ : classification) {
class_.probability /= sum;
}
};

// Normalize the input
auto classification_input = classification;
normalizeProbabilities(classification_input);

// Update the matched classification probability with a gain
for (const auto & new_class : classification_input) {
bool found = false;
for (auto & old_class : classification_) {
if (new_class.label == old_class.label) {
old_class.probability += new_class.probability * gain;
found = true;
break;
}
}
// If the label is not found, add it to the classification list
if (!found) {
auto adding_class = new_class;
adding_class.probability *= gain;
classification_.push_back(adding_class);
}
}

// If the probability is less than the threshold, remove the class
classification_.erase(
std::remove_if(
classification_.begin(), classification_.end(),
[remove_threshold](const auto & class_) { return class_.probability < remove_threshold; }),
classification_.end());

// Normalize tracking classification
normalizeProbabilities(classification_);
}

geometry_msgs::msg::PoseWithCovariance Tracker::getPoseWithCovariance(
const rclcpp::Time & time) const
{
Expand Down
Loading