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(autoware_lidar_centerpoint): add priority map to preprocess kernel and centerpoint_trt #9583

Conversation

technolojin
Copy link
Contributor

@technolojin technolojin commented Dec 6, 2024

Description

Current voxel processing is done by order of X, Y sequentially.
IF the number of filled voxel exceed the ML model limit, the detectable range is limited.

The priority map is set by a scalar field as following.

    // absolute rectangular hyperbola to focus on crosssection
    // multiply sigmoid function to prioritize the front area
    const float score_a = abs((pos_x - 15.0) * pos_y) * (1 / (1 + exp(pos_x * 0.3)) + 0.75);
    // ellipse area focus on (10,0) and (150,0)
    const float score_b = sqrt((pos_x - 150) * (pos_x - 150) + pos_y * pos_y) +
                          sqrt((pos_x - 10) * (pos_x - 10) + pos_y * pos_y) - 140;
    // total score with weight
    // add noise to extend detection area in low-score area
    const float score =
      sqrt(score_a * 0.1 + score_b * 2.5) + normal_distribution(generator) * score_b * 0.01;

Figure_2

The following visualization is to show filled voxel distribution. Configurations are as follwing.

  • input high-density lidar point cloud
  • score_threshold: 0.01
  • max_voxel_size: 40000
  • point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0]
    Then lower score object will be shown (due to the lower score_threshold), indirectly visualize where the voxel is filled.

Screenshot from 2024-11-29 18-19-04

Related links

Parent Issue:

  • Link

How was this PR tested?

Notes for reviewers

None.

Interface changes

None.

Effects on system behavior

None.

@technolojin technolojin self-assigned this Dec 6, 2024
@github-actions github-actions bot added component:perception Advanced sensor data processing and environment understanding. (auto-assigned) tag:require-cuda-build-and-test labels Dec 6, 2024
Copy link

github-actions bot commented Dec 6, 2024

Thank you for contributing to the Autoware project!

🚧 If your pull request is in progress, switch it to draft mode.

Please ensure:

@technolojin technolojin added the tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Dec 9, 2024
Copy link

codecov bot commented Dec 9, 2024

Codecov Report

Attention: Patch coverage is 0% with 26 lines in your changes missing coverage. Please review.

Project coverage is 29.48%. Comparing base (557a8b5) to head (4dbadba).
Report is 76 commits behind head on main.

Files with missing lines Patch % Lines
...autoware_lidar_centerpoint/lib/centerpoint_trt.cpp 0.00% 21 Missing ⚠️
...ar_centerpoint/lib/preprocess/preprocess_kernel.cu 0.00% 5 Missing ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##             main    #9583      +/-   ##
==========================================
- Coverage   29.49%   29.48%   -0.01%     
==========================================
  Files        1443     1444       +1     
  Lines      108648   108685      +37     
  Branches    41537    41546       +9     
==========================================
+ Hits        32047    32051       +4     
- Misses      73479    73512      +33     
  Partials     3122     3122              
Flag Coverage Δ *Carryforward flag
differential 6.41% <0.00%> (?)
total 29.49% <ø> (+<0.01%) ⬆️ Carriedforward from 557a8b5

*This pull request uses carry forward flags. Click here to find out more.

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

@technolojin technolojin marked this pull request as ready for review December 9, 2024 02:15
@knzo25
Copy link
Contributor

knzo25 commented Dec 9, 2024

I am quite opposed to this idea. Here are some of the reasons

  • it introduces random access (there already one in the affected method, but this adds another).
  • Going over the limit should not happen for a specific product/project. In the past, when faced with a similar situation the resolution was to simply increase the size (number of points, in the past). When using centerpoint, we are not limited by memory resources.
  • If this reaaaally needs to be added, I would want it to be enabled automatically when the first overflow of max voxels occurs, or as a parameter.
  • Looking ahead, there are talks of using finer voxels, or dynamic voxelization. In both cases the current voxelization does not scale (can take up to 100ms for some of the cases considered in our internal ml repository). For these cases, I am testing other implementations (e.g., hash), which would immediately make this inapplicable.
  • This is ML talk, but when deploying a ML algorithm in a distribution other than the one used for training, there will be inevitably some sort of degradation in performance (compared to the theoretical case of training on the right distribution). While we can not control all the distribution changes, we should not go out of our way to add more. Yes, adding voxels with priority is better than what happens with a low max number of voxels and without this PR, but remember that the induced distributions of the voxels when projected into the BEV space will change quite a lot, which is prone to cause unexpected phenomena

@technolojin
Copy link
Contributor Author

technolojin commented Dec 10, 2024

@knzo25
Thank you for your comments and opinion.

it introduces random access

Yes

Going over the limit should not happen for a specific product/project.

I agree. It is for worst cases.

I would want it to be enabled automatically when the first overflow of max voxels occurs,

The implementation will be complicated.

or as a parameter.

May be better option for users.

Looking ahead, there are talks of using finer voxels, or dynamic voxelization. In both cases the current voxelization does not scale (can take up to 100ms for some of the cases considered in our internal ml repository). For these cases, I am testing other implementations (e.g., hash), which would immediately make this inapplicable.

If better solution exist and can solve the current risk in a short time, I do not think this PR is needed. Are those will come soon?

distributions of the voxels when projected into the BEV space will change quite a lot, which is prone to cause unexpected phenomena

It may depends on the model. Is not the voxel inputs are treated as a set?
Only voxels filled by points will be collected, therefore spatial order is fluctuated anyway.

Alternative logic proposal

In current logic, the voxels are filled from right-hand side.

  • before
  int voxel_idx = floorf((x - min_x_range) / pillar_x_size);
  int voxel_idy = floorf((y - min_y_range) / pillar_y_size);
  unsigned int voxel_index = voxel_idy * grid_x_size + voxel_idx;

We can change it to fill from front to rear.

  • after
  int voxel_idx = floorf((x - min_x_range) / pillar_x_size);
  int voxel_idy = floorf((y - min_y_range) / pillar_y_size);
  unsigned int voxel_index = (grid_x_size - 1 - voxel_idx) * grid_y_size + voxel_idy;
  • Not a random access
  • its only orientation difference. spatial order may similar to the previous implementation

@knzo25 How about this?

@technolojin
Copy link
Contributor Author

Alternative PR #9608

@technolojin
Copy link
Contributor Author

This PR will be replaced by #9608

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
component:perception Advanced sensor data processing and environment understanding. (auto-assigned) tag:require-cuda-build-and-test tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants