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

fix(multi_object_tracker): make sure smallest unknown footprint is 0.3 #6618

Closed

Conversation

mebasoglu
Copy link
Contributor

@mebasoglu mebasoglu commented Mar 14, 2024

Description

Related issue:

When unknown object polygon has only one point which is 0,0,0 , the node dies.

Related links

Fixes: #6617

Tests performed

Confirmed on logging simulator.

Notes for reviewers

There are two places where this error occurs, on data_association.cpp and multi_object_tracker_core.cpp. The fix was added those.

Interface changes

Effects on system behavior

Pre-review checklist for the PR author

The PR author must check the checkboxes below when creating the PR.

In-review checklist for the PR reviewers

The PR reviewers must check the checkboxes below before approval.

  • The PR follows the pull request guidelines.
  • The PR has been properly tested.
  • The PR has been reviewed by the code owners.

Post-review checklist for the PR author

The PR author must check the checkboxes below before merging.

  • There are no open discussions or they are tracked via tickets.
  • The PR is ready for merge.

After all checkboxes are checked, anyone who has write access can merge the PR.

@github-actions github-actions bot added the component:perception Advanced sensor data processing and environment understanding. (auto-assigned) label Mar 14, 2024
@@ -386,6 +386,15 @@ void MultiObjectTracker::sanitizeTracker(
continue;
}

if (
object1.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON &&
tier4_autoware_utils::getArea(object1.shape) == 0 &&
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It is not very desirable to make equal comparisons between floating-point types and direct numbers. 🙏
In this case, it is 0, so it is OK, but it may cause unintended bugs.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@yukkysaito can we use the following directly directly:

/**
* @brief
* https://randomascii.wordpress.com/2012/02/25/comparing-floating-point-numbers-2012-edition/
* @pre rel_eps >= 0
* @return True iff 'a' and 'b' are within relative 'rel_eps' of each other.
*/
template <typename T>
bool rel_eq(const T & a, const T & b, const T & rel_eps)
{
static_assert(
std::is_floating_point<T>::value, "Float comparisons only support floating point types.");
const auto delta = std::abs(a - b);
const auto larger = std::max(std::abs(a), std::abs(b));
const auto max_rel_delta = (larger * rel_eps);
return delta <= max_rel_delta;
}

Or do we have these float comparisons somewhere else?

@yukkysaito
Copy link
Contributor

Thanks for your PR 👍
We'll check this

@mebasoglu mebasoglu force-pushed the fix-multi-obj-tracker branch from 35ea36d to 831d01a Compare March 15, 2024 13:06
@armaganarsln armaganarsln force-pushed the fix-multi-obj-tracker branch from 831d01a to 156b114 Compare March 15, 2024 14:30
@armaganarsln armaganarsln added the tag:pr-agent Mark to enable PR-Agent for automated reviews. (used-by-ci) label Mar 15, 2024
@armaganarsln
Copy link

/ask rate this PR quality, from 1 to 10. explain why

Copy link

Question: rate this pr quality, from 1 to 10. explain why

Answer:
I would rate this PR as an 8.

The author has provided a clear and concise description of the problem and the solution. The PR addresses a specific issue (#6617) and the author has tested the changes in a logging simulator.

The code changes are straightforward and easy to understand. The author has added checks to ensure that when an unknown object polygon has only one point which is 0,0,0, it doesn't cause the node to die. Instead, it sets the x, y, and z values of the point to 0.3.

However, there are a few areas where the PR could be improved:

  1. The PR could benefit from more extensive testing. It's not clear if the changes have been tested in a variety of scenarios or just one. More comprehensive testing could help ensure that the changes don't introduce new issues.

  2. The PR could also benefit from more detailed comments in the code. While the changes are relatively straightforward, additional comments could help other developers understand why these specific changes were made.

  3. The PR doesn't mention if there are any potential side effects of these changes. While it seems unlikely given the nature of the changes, it's always good to consider and document potential side effects.

  4. The PR checklist is not fully checked, which indicates that the PR might not be ready for review or merge.

Overall, the PR is of good quality but there's room for improvement.


✨ Ask tool usage guide:

Overview:
The ask tool answers questions about the PR, based on the PR code changes.
It can be invoked manually by commenting on any PR:

/ask "..."

Note that the tool does not have "memory" of previous questions, and answers each question independently.

More PR-Agent commands

To invoke the PR-Agent, add a comment using one of the following commands:

  • /review: Request a review of your Pull Request.
  • /describe: Update the PR title and description based on the contents of the PR.
  • /improve [--extended]: Suggest code improvements. Extended mode provides a higher quality feedback.
  • /ask <QUESTION>: Ask a question about the PR.
  • /update_changelog: Update the changelog based on the PR's contents.
  • /add_docs 💎: Generate docstring for new components introduced in the PR.
  • /generate_labels 💎: Generate labels for the PR based on the PR's contents.
  • /analyze 💎: Automatically analyzes the PR, and presents changes walkthrough for each component.

See the tools guide for more details.
To list the possible configuration parameters, add a /config comment.

See the ask usage page for a comprehensive guide on using this tool.

@armaganarsln
Copy link

/review

Copy link

PR Review

⏱️ Estimated effort to review [1-5]

3, because the changes involve critical sections of the code related to object tracking and data association, which are complex areas in autonomous driving systems. Understanding the implications of these changes requires a good grasp of the system's overall architecture and the specific modules affected.

🧪 Relevant tests

No

🔍 Possible issues

Possible Bug: The modification of measurement_object directly within the loop may not have the intended effect since it's a copy of the object from the vector, not a reference. This could lead to unexpected behavior where the changes do not persist outside the loop.

Hardcoded Values: The use of hardcoded values (0.3) for adjusting the footprint points lacks flexibility and may not be suitable for all scenarios or object sizes.

🔒 Security concerns

No

Code feedback:
relevant fileperception/multi_object_tracker/src/data_association/data_association.cpp
suggestion      

Consider using a reference or pointer to modify measurement_object within the loop to ensure changes persist as intended. This approach will allow modifications to reflect on the actual object in the measurements.objects vector. [important]

relevant lineautoware_auto_perception_msgs::msg::DetectedObject measurement_object =

relevant fileperception/multi_object_tracker/src/data_association/data_association.cpp
suggestion      

Introduce a configurable parameter for the minimum footprint size (0.3) to enhance flexibility and adaptability to different scenarios or object sizes. This could be implemented as a node parameter or a constant defined at a higher scope. [important]

relevant linemeasurement_object.shape.footprint.points.front().x = 0.3;

relevant fileperception/multi_object_tracker/src/multi_object_tracker_core.cpp
suggestion      

Similar to the previous suggestion, use a reference or pointer when modifying object1 to ensure that changes to the footprint points are reflected in the original object list. This is crucial for maintaining data integrity throughout the processing pipeline. [important]

relevant lineobject1.shape.footprint.points.front().x = 0.3;

relevant fileperception/multi_object_tracker/src/multi_object_tracker_core.cpp
suggestion      

Implement a utility function to handle the adjustment of footprint points for objects with zero area. This function can encapsulate the logic for checking the object's shape type, area, and footprint points size, thereby improving code modularity and readability. [medium]

relevant lineobject1.shape.footprint.points.front().x = 0.3;


✨ Review tool usage guide:

Overview:
The review tool scans the PR code changes, and generates a PR review. The tool can be triggered automatically every time a new PR is opened, or can be invoked manually by commenting on any PR.
When commenting, to edit configurations related to the review tool (pr_reviewer section), use the following template:

/review --pr_reviewer.some_config1=... --pr_reviewer.some_config2=...

With a configuration file, use the following template:

[pr_reviewer]
some_config1=...
some_config2=...
Utilizing extra instructions

The review tool can be configured with extra instructions, which can be used to guide the model to a feedback tailored to the needs of your project.

Be specific, clear, and concise in the instructions. With extra instructions, you are the prompter. Specify the relevant sub-tool, and the relevant aspects of the PR that you want to emphasize.

Examples for extra instructions:

[pr_reviewer] # /review #
extra_instructions="""
In the 'possible issues' section, emphasize the following:
- Does the code logic cover relevant edge cases?
- Is the code logic clear and easy to understand?
- Is the code logic efficient?
...
"""

Use triple quotes to write multi-line instructions. Use bullet points to make the instructions more readable.

How to enable\disable automation
  • When you first install PR-Agent app, the default mode for the review tool is:
pr_commands = ["/review", ...]

meaning the review tool will run automatically on every PR, with the default configuration.
Edit this field to enable/disable the tool, or to change the used configurations

Auto-labels

The review tool can auto-generate two specific types of labels for a PR:

  • a possible security issue label, that detects possible security issues (enable_review_labels_security flag)
  • a Review effort [1-5]: x label, where x is the estimated effort to review the PR (enable_review_labels_effort flag)
Extra sub-tools

The review tool provides a collection of possible feedbacks about a PR.
It is recommended to review the possible options, and choose the ones relevant for your use case.
Some of the feature that are disabled by default are quite useful, and should be considered for enabling. For example:
require_score_review, require_soc2_ticket, and more.

Auto-approve PRs

By invoking:

/review auto_approve

The tool will automatically approve the PR, and add a comment with the approval.

To ensure safety, the auto-approval feature is disabled by default. To enable auto-approval, you need to actively set in a pre-defined configuration file the following:

[pr_reviewer]
enable_auto_approval = true

(this specific flag cannot be set with a command line argument, only in the configuration file, committed to the repository)

You can also enable auto-approval only if the PR meets certain requirements, such as that the estimated_review_effort is equal or below a certain threshold, by adjusting the flag:

[pr_reviewer]
maximal_review_effort = 5
More PR-Agent commands

To invoke the PR-Agent, add a comment using one of the following commands:

  • /review: Request a review of your Pull Request.
  • /describe: Update the PR title and description based on the contents of the PR.
  • /improve [--extended]: Suggest code improvements. Extended mode provides a higher quality feedback.
  • /ask <QUESTION>: Ask a question about the PR.
  • /update_changelog: Update the changelog based on the PR's contents.
  • /add_docs 💎: Generate docstring for new components introduced in the PR.
  • /generate_labels 💎: Generate labels for the PR based on the PR's contents.
  • /analyze 💎: Automatically analyzes the PR, and presents changes walkthrough for each component.

See the tools guide for more details.
To list the possible configuration parameters, add a /config comment.

See the review usage page for a comprehensive guide on using this tool.

@armaganarsln
Copy link

/improve --extended

Copy link

github-actions bot commented Mar 15, 2024

PR Code Suggestions

CategorySuggestions                                                                                                                                                       
Maintainability
Encapsulate footprint size modification in a separate function.

Instead of directly modifying measurement_object.shape.footprint.points.front(), consider
creating a function that handles the modification of the footprint size. This function can
encapsulate the logic for setting the minimum footprint size, making the code more modular
and easier to maintain.

perception/multi_object_tracker/src/data_association/data_association.cpp [210-215]

-if (
-  measurement_object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON &&
-  area == 0 && measurement_object.shape.footprint.points.size() == 1) {
-  measurement_object.shape.footprint.points.front().x = 0.3;
-  measurement_object.shape.footprint.points.front().y = 0.3;
-  measurement_object.shape.footprint.points.front().z = 0.3;
-}
+ensureMinimumFootprintSize(measurement_object);
 
Use a function to set the minimum footprint size, reducing code duplication.

Similar to the previous suggestion, encapsulate the logic for setting the minimum
footprint size in a function. This avoids code duplication and makes future modifications
easier.

perception/multi_object_tracker/src/multi_object_tracker_core.cpp [390-396]

-if (
-  object1.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON &&
-  tier4_autoware_utils::getArea(object1.shape) == 0 &&
-  object1.shape.footprint.points.size() == 1) {
-  object1.shape.footprint.points.front().x = 0.3;
-  object1.shape.footprint.points.front().y = 0.3;
-  object1.shape.footprint.points.front().z = 0.3;
-}
+ensureMinimumFootprintSize(object1);
 
Possible issue
Add checks to prevent potential out-of-range exceptions.

Consider checking the return value of measurements.objects.at(measurement_idx) for
potential exceptions. Using .at() can throw an out-of-range exception if measurement_idx
is not a valid index. It might be safer to handle or prevent this potential exception.

perception/multi_object_tracker/src/data_association/data_association.cpp [162-163]

-autoware_auto_perception_msgs::msg::DetectedObject measurement_object =
-  measurements.objects.at(measurement_idx);
+if (measurement_idx < measurements.objects.size()) {
+  autoware_auto_perception_msgs::msg::DetectedObject measurement_object =
+    measurements.objects.at(measurement_idx);
+} else {
+  // Handle the error or ensure measurement_idx is always valid.
+}
 
Enhancement
Store function result in a variable to avoid multiple calls and improve readability.

To improve readability and maintainability, consider storing the result of
tier4_autoware_utils::getArea(measurement_object.shape) in a variable before the if
statement. This avoids calling the function multiple times and makes the code cleaner.

perception/multi_object_tracker/src/data_association/data_association.cpp [183-187]

 const double area = tier4_autoware_utils::getArea(measurement_object.shape);
-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);
-  if (area < min_area || max_area < area) passed_gate = false;
+if (passed_gate && (area < min_area_matrix_(tracker_label, measurement_label) || max_area_matrix_(tracker_label, measurement_label) < area)) {
+  passed_gate = false;
 }
 
Best practice
Define a constant for the minimum footprint size to improve maintainability.

For consistency and to avoid magic numbers, consider defining a constant for the minimum
footprint size (0.3) used in multiple places. This makes the code easier to maintain and
understand.

perception/multi_object_tracker/src/data_association/data_association.cpp [213-215]

-measurement_object.shape.footprint.points.front().x = 0.3;
-measurement_object.shape.footprint.points.front().y = 0.3;
-measurement_object.shape.footprint.points.front().z = 0.3;
+constexpr double MIN_FOOTPRINT_SIZE = 0.3;
+measurement_object.shape.footprint.points.front().x = MIN_FOOTPRINT_SIZE;
+measurement_object.shape.footprint.points.front().y = MIN_FOOTPRINT_SIZE;
+measurement_object.shape.footprint.points.front().z = MIN_FOOTPRINT_SIZE;
 

✨ Improve tool usage guide:

Overview:
The improve tool scans the PR code changes, and automatically generates suggestions for improving the PR code. The tool can be triggered automatically every time a new PR is opened, or can be invoked manually by commenting on a PR.
When commenting, to edit configurations related to the improve tool (pr_code_suggestions section), use the following template:

/improve --pr_code_suggestions.some_config1=... --pr_code_suggestions.some_config2=...

With a configuration file, use the following template:

[pr_code_suggestions]
some_config1=...
some_config2=...
Enabling\disabling automation

When you first install the app, the default mode for the improve tool is:

pr_commands = ["/improve --pr_code_suggestions.summarize=true", ...]

meaning the improve tool will run automatically on every PR, with summarization enabled. Delete this line to disable the tool from running automatically.

Utilizing extra instructions

Extra instructions are very important for the improve tool, since they enable to guide the model to suggestions that are more relevant to the specific needs of the project.

Be specific, clear, and concise in the instructions. With extra instructions, you are the prompter. Specify relevant aspects that you want the model to focus on.

Examples for extra instructions:

[pr_code_suggestions] # /improve #
extra_instructions="""
Emphasize the following aspects:
- Does the code logic cover relevant edge cases?
- Is the code logic clear and easy to understand?
- Is the code logic efficient?
...
"""

Use triple quotes to write multi-line instructions. Use bullet points to make the instructions more readable.

A note on code suggestions quality
  • While the current AI for code is getting better and better (GPT-4), it's not flawless. Not all the suggestions will be perfect, and a user should not accept all of them automatically.
  • Suggestions are not meant to be simplistic. Instead, they aim to give deep feedback and raise questions, ideas and thoughts to the user, who can then use his judgment, experience, and understanding of the code base.
  • Recommended to use the 'extra_instructions' field to guide the model to suggestions that are more relevant to the specific needs of the project, or use the custom suggestions 💎 tool
  • With large PRs, best quality will be obtained by using 'improve --extended' mode.
More PR-Agent commands

To invoke the PR-Agent, add a comment using one of the following commands:

  • /review: Request a review of your Pull Request.
  • /describe: Update the PR title and description based on the contents of the PR.
  • /improve [--extended]: Suggest code improvements. Extended mode provides a higher quality feedback.
  • /ask <QUESTION>: Ask a question about the PR.
  • /update_changelog: Update the changelog based on the PR's contents.
  • /add_docs 💎: Generate docstring for new components introduced in the PR.
  • /generate_labels 💎: Generate labels for the PR based on the PR's contents.
  • /analyze 💎: Automatically analyzes the PR, and presents changes walkthrough for each component.

See the tools guide for more details.
To list the possible configuration parameters, add a /config comment.

See the improve usage page for a more comprehensive guide on using this tool.

@armaganarsln
Copy link

/ask At line 391 of multi_object_tracker_core.cpp, I'm comparing a float against an integer tier4_autoware_utils::getArea(object1.shape) == 0 I don't think this is a good thing. What should I do instead?

Copy link

Question: at line 391 of multi_object_tracker_core.cpp, i'm comparing a float against an integer tier4_autoware_utils::getarea(object1.shape) == 0 i don't think this is a good thing. what should i do instead?

Answer:
Comparing a float to an integer directly can indeed lead to precision issues due to the way floating point numbers are represented in memory. A better approach would be to use a small threshold value for the comparison.

Instead of tier4_autoware_utils::getArea(object1.shape) == 0, you could use something like:

const float epsilon = 1e-9; // or any other small value that suits your precision needs
if (std::abs(tier4_autoware_utils::getArea(object1.shape)) < epsilon) {
    // ...
}

This way, you're checking if the area is "close enough" to zero, taking into account the precision of floating point numbers.


✨ Ask tool usage guide:

Overview:
The ask tool answers questions about the PR, based on the PR code changes.
It can be invoked manually by commenting on any PR:

/ask "..."

Note that the tool does not have "memory" of previous questions, and answers each question independently.

More PR-Agent commands

To invoke the PR-Agent, add a comment using one of the following commands:

  • /review: Request a review of your Pull Request.
  • /describe: Update the PR title and description based on the contents of the PR.
  • /improve [--extended]: Suggest code improvements. Extended mode provides a higher quality feedback.
  • /ask <QUESTION>: Ask a question about the PR.
  • /update_changelog: Update the changelog based on the PR's contents.
  • /add_docs 💎: Generate docstring for new components introduced in the PR.
  • /generate_labels 💎: Generate labels for the PR based on the PR's contents.
  • /analyze 💎: Automatically analyzes the PR, and presents changes walkthrough for each component.

See the tools guide for more details.
To list the possible configuration parameters, add a /config comment.

See the ask usage page for a comprehensive guide on using this tool.

@xmfcx xmfcx mentioned this pull request Mar 15, 2024
4 tasks
@@ -207,6 +207,13 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
if (passed_gate) {
const double min_iou = min_iou_matrix_(tracker_label, measurement_label);
const double min_union_iou_area = 1e-2;
if (
measurement_object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON &&
area == 0 && measurement_object.shape.footprint.points.size() == 1) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
area == 0 && measurement_object.shape.footprint.points.size() == 1) {
area == 0 && measurement_object.shape.footprint.points.size() == 1) {

Same as here https://github.com/autowarefoundation/autoware.universe/pull/6618/files#r1525002210

Comment on lines 210 to 216
if (
measurement_object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON &&
area == 0 && measurement_object.shape.footprint.points.size() == 1) {
measurement_object.shape.footprint.points.front().x = 0.3;
measurement_object.shape.footprint.points.front().y = 0.3;
measurement_object.shape.footprint.points.front().z = 0.3;
}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

To set it to 0.3 would embed an unintended bug.In fact.
It sometimes results in strange behavior when there are actually objects with smaller values.
I think a better way to handle this issue is to have the getIntersectionArea function return 0 if the polygon does not have 3 or more points in it.

Copy link
Contributor

@YoshiRi YoshiRi left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this issue should be solved with fixing IoU caluculate function, so I do not want to apply this PR.
See #6617 (comment) .

@mebasoglu mebasoglu force-pushed the fix-multi-obj-tracker branch 2 times, most recently from 694ea7e to 959bfe6 Compare March 18, 2024 11:39
@github-actions github-actions bot added component:common Common packages from the autoware-common repository. (auto-assigned) and removed component:perception Advanced sensor data processing and environment understanding. (auto-assigned) labels Mar 18, 2024
@mebasoglu
Copy link
Contributor Author

Hello everyone, thank you for the feedback. I have pushed a commit for get2dIoU. Now, if there aren't enough points for a polygon, it will return 0.0. It works on logging simulator.

The other approach was checking points size in getIntersectionArea function. That will also affect get2dGeneralizedIoU,
get2dPrecision and get2dRecall.

What do you think about applying the patch to getIntersectionArea, or should it be only for get2dIoU?

@mebasoglu mebasoglu force-pushed the fix-multi-obj-tracker branch from 959bfe6 to 7bbe740 Compare March 18, 2024 12:38
@YoshiRi
Copy link
Contributor

YoshiRi commented Mar 19, 2024

@mebasoglu
Thanks for your work!

As you say, changing getIntersectionArea may better since most function you mentioned has following escape sequence. I prefer this approach.

  const double intersection_area = getIntersectionArea(source_polygon, target_polygon);
  if (intersection_area == 0.0) return 0.0; // you can escape here

But it seems get2dGeneralizedIoU do not have the escape, so we need to do some work then.

  const double intersection_area = getIntersectionArea(source_polygon, target_polygon); // no escape
  const double union_area = getUnionArea(source_polygon, target_polygon); // this part may cause error
  const double convex_shape_area = getConvexShapeArea(source_polygon, target_polygon); // this will cause error

It would be helpful if you could change getUnionArea, getConvexShapeArea and getIntersectionArea.

Copy link
Contributor

@technolojin technolojin left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for your bug report and your effort for the solution.

I agree to add checkers insures that the two inputs are valid.

The boost documentation of intersection mentioned as following.
"Check the Polygon Concept for the rules that polygon input for this algorithm should fulfill"

Having at least 3 footprint points is a necessary condition, not the sufficient condition. to have an area, the sufficient condition is to have the rank of 2.

I would like to suggest to add checkers of the validity of the polygon, as following.

static const double MIN_AREA = 1e-9;
if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0;
if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0;

In the official documentation of the area function,
"
Behavior
pointlike (e.g. point) Returns 0
linear (e.g. linestring) Returns 0
areal (e.g. polygon) Returns the area
"
Additionally, the checker makes to avoid division by a small number.

The checkers may implied in the necessary functions, such as get2dIoU, get2dGeneralizedIoU, get2dPrecision, and get2dRecall.

My suggestion is as following. I did not test with the issue data.
https://github.com/technolojin/autoware.universe/blob/f22408ad23c79d92bc7dba3cd48e407358ff2f8e/common/object_recognition_utils/include/object_recognition_utils/matching.hpp

Signed-off-by: Mehmet Emin BAŞOĞLU <mehmeteminbasoglu@hotmail.com>
@mebasoglu mebasoglu force-pushed the fix-multi-obj-tracker branch from 7bbe740 to ac5c65a Compare March 19, 2024 10:37
Signed-off-by: Mehmet Emin BAŞOĞLU <mehmeteminbasoglu@hotmail.com>
@mebasoglu
Copy link
Contributor Author

Hello @YoshiRi @technolojin , thank you very much for the feedback.

I have created a new function validatePolygons . It returns false if the polygon areas are very close to zero, true otherwise. I added checks with this function on getConvexShapeArea, getIntersectionArea and getUnionArea. They return 0.0 if polygons aren't validated.

The get2dGeneralizedIoU function was also updated for the checks.

Tested on logging simulator.

@technolojin
Copy link
Contributor

@mebasoglu Thank you for your update.
Your solution is a simple solution and it is important. However, I would like to give you some feedback.

  1. Numerical error
    As @mebasoglu checked, comparing a float number against zero (even the type is float) have a risk since the target number (intersection_area for example) can have a numerical error (overflow if this number is used for division, and that is what we do here).

    Here are some related discussions.
    https://softwareengineering.stackexchange.com/questions/309350/avoiding-division-by-zero-using-float-comparison
    https://en.wikipedia.org/wiki/Machine_epsilon

Question: at line 391 of multi_object_tracker_core.cpp, i'm comparing a float against an integer tier4_autoware_utils::getarea(object1.shape) == 0 i don't think this is a good thing. what should i do instead?

Answer: Comparing a float to an integer directly can indeed lead to precision issues due to the way floating point numbers are represented in memory. A better approach would be to use a small threshold value for the comparison.

Instead of tier4_autoware_utils::getArea(object1.shape) == 0, you could use something like:

const float epsilon = 1e-9; // or any other small value that suits your precision needs
if (std::abs(tier4_autoware_utils::getArea(object1.shape)) < epsilon) {
    // ...
}

This way, you're checking if the area is "close enough" to zero, taking into account the precision of floating point numbers.
✨ Ask tool usage guide:

  1. Meaning of returning 0.0 on getConvexShapeArea and getUnionArea functions
    As your updated functions, getConvexShapeArea and getUnionArea returns zero even one polygon have a valid area. As future users, it is confusing result. You implemented to check if the obtained area is zero before calculate necessary ratios, but other future developer may not understand the meaning and can cause catastrophic error (divide-by-zero).
    (Returning zero on getIntersectionArea is valid, by its definition.)

  2. Duplicated checks
    In get2dGeneralizedIoU, the validatePolygons runs three times. and it is not necessary.
    The IoU calculations will repeated many many times and this change can make overall object tracking heavy, especially the number of tracking and detected object is large.
    (For example, calculation of matching score matrix have complexity of O(n^2))

I would like to request an efficient solution. Even it becomes a bit complicate, I think it worth.

@YoshiRi YoshiRi added the run:build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Mar 20, 2024
@mebasoglu
Copy link
Contributor Author

Closing due to #6701 was merged.

@mebasoglu mebasoglu closed this Apr 3, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
component:common Common packages from the autoware-common repository. (auto-assigned) run:build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) tag:pr-agent Mark to enable PR-Agent for automated reviews. (used-by-ci)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

multi_object_tracker dies when unknown object has only one point in footprint which is 0,0,0
6 participants