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: add ring based filter for velodyne #69

Open
wants to merge 13 commits into
base: main
Choose a base branch
from

Conversation

mebasoglu
Copy link
Collaborator

@mebasoglu mebasoglu commented Sep 6, 2023

PR Type

  • New Feature

Related Links

The issue: #60

Description

This is an implementation for a ring based filter. It removes points if they are within specified angle ranges.

Review Procedure

There are two new parameters: enable_ring_section_filter and excluded_ring_sectors on velodyne_decoder_ros_wrapper.cpp.

enable_ring_section_filter is a boolean to activate the filter.

excluded_ring_sectors is a string which holds a list of excluded sectors. [12, 31110, 31495], [], []

An excluded region is a list which holds ring, start angle and end angle. [12, 31110, 31495]

Since ROS 2 doesn't support setting parameters as a list of lists, nlohmann-json-dev library has been used.
excluded_ring_sectors string is parsed using the library.


On nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp
file a new function has been added check_excluded_point.

This function takes channel id and azimuth angle of the point and checks if the point inside any of the regions specified
for that ring.

The function was used in vlp16_decoder.hpp, vlp32_decoder.hpp and vlp128_decoder.hpp.


A sample usage has been added to velodyne_launch_all_hw.xml.

<node pkg="nebula_ros" exec="velodyne_driver_ros_wrapper_node"
      name="velodyne_cloud" output="screen">
  ...
  <param name="enable_ring_section_filter" value="true"/>
  <param name="excluded_ring_sectors" type="str"
         value="[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]"/>
</node>

Here is a sample bag file which has only /velodyne_packets of a VLP16 to test: https://drive.google.com/drive/folders/1LY_Nyt5Z_M6rG4juSB1UiKk9IFBKVxU7?usp=sharing

These parameters were used for the bag:

<arg name="enable_ring_section_filter" default="true"/>
<arg name="excluded_ring_sectors"
         default="'[[12, 31110, 31495], [0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600], [4, 3000, 4300], [5, 2950, 4050], [6, 3100, 3800], [0, 26000, 32200], [1, 26000, 32200], [2, 26000, 31000], [3, 26000, 30000], [4, 26000, 28000]]'"/>

Remarks

Comparison between main branch and this PR:
Timing_comparison

main ring_filter
d_total AVG 0.363243 0.469112
n_out AVG 15869.5 15869.5
d_total STD 0.108956 0.109353
n_out STD 262.889 262.889
d_total AVG % rel to main 100 129.146
n_out AVG % rel to main 100 100
d_total STD % rel to main 100 100.364
n_out STD % rel to main 100 100

Without the filter, we have reflected points which are under the ground:
filter_off

With the filter:
filter_on

Pre-Review Checklist for the PR Author

PR Author should check the checkboxes below when creating the PR.

  • Assign PR to reviewer

Checklist for the PR Reviewer

Reviewers should check the checkboxes below before approval.

  • Commits are properly organized and messages are according to the guideline
  • (Optional) Unit tests have been written for new behavior
  • PR title describes the changes

Post-Review Checklist for the PR Author

PR Author should check the checkboxes below before merging.

  • All open points are addressed and tracked via issues or tickets

CI Checks

  • Build and test for PR: Required to pass before the merge.

@mebasoglu mebasoglu changed the title Memin/dev/ring based filter feat: add ring based filter for velodyne Sep 6, 2023
@codecov-commenter
Copy link

codecov-commenter commented Sep 6, 2023

Codecov Report

Attention: Patch coverage is 8.51064% with 43 lines in your changes are missing coverage. Please review.

Project coverage is 9.21%. Comparing base (1ae3f75) to head (0ae17b5).

Files Patch % Lines
..._ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp 0.00% 32 Missing ⚠️
...coders_velodyne/decoders/velodyne_scan_decoder.hpp 0.00% 4 Missing and 2 partials ⚠️
...ebula_decoders_velodyne/decoders/vlp32_decoder.cpp 0.00% 3 Missing ⚠️
...ebula_decoders_velodyne/decoders/vlp16_decoder.cpp 66.66% 0 Missing and 1 partial ⚠️
...bula_decoders_velodyne/decoders/vls128_decoder.cpp 66.66% 0 Missing and 1 partial ⚠️

❗ Your organization needs to install the Codecov GitHub app to enable full functionality.

Additional details and impacted files
@@           Coverage Diff            @@
##            main     #69      +/-   ##
========================================
+ Coverage   4.84%   9.21%   +4.37%     
========================================
  Files        249      78     -171     
  Lines      19210    9384    -9826     
  Branches    1075    1060      -15     
========================================
- Hits         931     865      -66     
+ Misses     17579    7820    -9759     
+ Partials     700     699       -1     
Flag Coverage Δ
differential 9.21% <8.51%> (?)
total ?

Flags with carried forward coverage won't be shown. Click here to find out more.

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

@amc-nu
Copy link
Contributor

amc-nu commented Sep 11, 2023

This looks like an interesting feature.
However, I think this should be implemented as a composable node for any current and future lidar model.

@mebasoglu
Copy link
Collaborator Author

This looks like an interesting feature. However, I think this should be implemented as a composable node for any current and future lidar model.

Hello @amc-nu , do you mean a new composable node inside Nebula or inside Autoware sensing pipeline? My idea was to implement it inside the driver so that the delay will be lower.

@mebasoglu mebasoglu marked this pull request as draft January 26, 2024 11:38
@mebasoglu mebasoglu self-assigned this Jan 26, 2024
@mebasoglu mebasoglu force-pushed the memin/dev/ring-based-filter branch from 78ee135 to 77a4781 Compare March 8, 2024 09:45
@mebasoglu mebasoglu marked this pull request as ready for review March 8, 2024 12:42
@mebasoglu
Copy link
Collaborator Author

Hello @drwnz , this PR is ready for a review.

@drwnz drwnz requested review from drwnz and amc-nu March 11, 2024 09:03
@mebasoglu mebasoglu force-pushed the memin/dev/ring-based-filter branch 2 times, most recently from deaea10 to 6154ce8 Compare March 19, 2024 09:35
@mebasoglu mebasoglu force-pushed the memin/dev/ring-based-filter branch from 6154ce8 to 0ae17b5 Compare April 1, 2024 09:45
README.md Outdated Show resolved Hide resolved
README.md Outdated
| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle |
| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle |
| invalid_point_remove | bool | false | true, false | Enable ring based filter* |
| invalid_regions | string | | | Invalid point regions to remove* |
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
| invalid_regions | string | | | Invalid point regions to remove* |
| excluded_ring_sectors | string | | | Identifies and prevents specific ring sectors from being included in the point cloud based on ring ID, start angle, and end angle. |

README.md Outdated
Comment on lines 228 to 234
*`invalid_point_remove` activates the ring based filter which removes points if they are within specified angle ranges.

*The format for an invalid region is [ring_id, start_angle, end_angle]

*Angles are given in degrees and multiplied by 100. For instance, 34.44 degrees is represented as 3444.

*Invalid regions are specified as a string containing a list of invalid regions. Ensure that you have quotation marks to make it string. For example:
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
*`invalid_point_remove` activates the ring based filter which removes points if they are within specified angle ranges.
*The format for an invalid region is [ring_id, start_angle, end_angle]
*Angles are given in degrees and multiplied by 100. For instance, 34.44 degrees is represented as 3444.
*Invalid regions are specified as a string containing a list of invalid regions. Ensure that you have quotation marks to make it string. For example:
- `enable_ring_section_filter` toggles a ring-based filter to remove points located within predefined angle ranges.
- Specify an excluded section using the format `[ring_id, start_angle, end_angle]`.
- Angles must be in degrees, scaled by a factor of 100. For example, represent `34.44` degrees as `3444`.
- It's possible to define multiple excluded regions for the same ring, allowing for versatile filtering configurations.
- Define excluded regions as a string containing a list of such regions, enclosed in quotation marks. For instance:

README.md Outdated
Comment on lines 243 to 244

*Multiple invalid regions are possible for the same ring.
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
*Multiple invalid regions are possible for the same ring.

README.md Outdated
name="velodyne_cloud" output="screen">
...
<param name="invalid_point_remove" value="true"/>
<param name="invalid_regions" value="'[[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]]'"/>
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
<param name="invalid_regions" value="'[[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]]'"/>
<param name="invalid_regions" value="'[[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]]'"/>

Why do we need the additional single quotes?

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Hello, since ROS 2 doesn't support setting parameters as a list of lists, Boost Property Tree library has been used.
invalid_regions is assumed as a string and parsed with the library. To make it string, I have added another set of quotes.

Comment on lines 18 to 19
#include "boost/property_tree/json_parser.hpp"
#include "boost/property_tree/ptree.hpp"
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
#include "boost/property_tree/json_parser.hpp"
#include "boost/property_tree/ptree.hpp"
#include <nlohmann/json.hpp>

Let's use this instead, boost is too heavy for this task.

<depend>nlohmann-json-dev</depend> can be added to the package.xml file and all should work fine.

And the rest of the code will be much cleaner and also will be error checked:

// Assuming `nlohmann::json` namespace is available as `json`
void parseInvalidRegions(const std::string& regions_json) {
    // Parse the JSON string
    auto invalid_regions_json = json::parse(regions_json);

    // Clear existing regions
    sensor_configuration_.invalid_regions.clear();

    // Iterate over the parsed JSON array
    for (const auto& region : invalid_regions_json) {
        // Extract the ring number, start angle, and end angle from each sub-array
        int ring_number = region[0];
        uint16_t start = region[1];
        uint16_t end = region[2];

        // Add the InvalidRegion to the map under the corresponding ring number
        sensor_configuration_.invalid_regions[ring_number].emplace_back(InvalidRegion{start, end});
    }
}

@mebasoglu mebasoglu force-pushed the memin/dev/ring-based-filter branch 2 times, most recently from 99d5413 to 847c1a7 Compare April 16, 2024 14:50
@mebasoglu
Copy link
Collaborator Author

Hello @xmfcx , I updated the PR. Could you please have another look?

@mebasoglu
Copy link
Collaborator Author

Hello @drwnz @mojomex , could you please review this PR? Maybe we can merge it before #138

Copy link
Collaborator

@drwnz drwnz 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 the PR, and apologies for the delay in review!
We would really like to apply this methodology to Hesai decoders as well, so if you can look at the suggested changes, we will proceed quickly to review. Mostly, if we are to adopt throughout multiple sensor manufacturers and models, we need to make sure to minimize the performance cost.

@@ -182,6 +182,19 @@ class VelodyneScanDecoder
virtual void reset_pointcloud(size_t n_pts, double time_stamp) = 0;
/// @brief Resetting overflowed point cloud buffer
virtual void reset_overflow(double time_stamp) = 0;

Copy link
Collaborator

Choose a reason for hiding this comment

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

This check has to be calculated with a search in the excluded regions parameters for every point, which is causing the performance overhead. We suggest pre-computing the binary value for each azimuth and channel value to make a map, allowing a single conditional to check if the point is valid or not.

@drwnz drwnz requested a review from mojomex June 12, 2024 12:55
Copy link
Collaborator

@mojomex mojomex left a comment

Choose a reason for hiding this comment

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

@mebasoglu Thank you for your contribution!
I'm sorry for responding that late 🙇 but here is my review.

The feature itself looks great and is a nice addition to Nebula but I would like you to refactor the filter code into its own isolated class as much as possible to properly separate the sensor features from Nebula features. Please respond to the comments I left above.

Thank you!


- `enable_ring_section_filter` toggles a ring-based filter to remove points located within predefined angle ranges.
- Specify an excluded section using the format `[ring_id, start_angle, end_angle]`.
- Angles must be in degrees, scaled by a factor of 100. For example, represent `34.44` degrees as `3444`.
Copy link
Collaborator

Choose a reason for hiding this comment

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

In my opinion, it would be more user-friendly to have a float here (34.44) and for Nebula to convert it to an int 3444 internally.

Comment on lines +15 to +21
/// @brief Invalid region on the cloud to be removed. `start` and `end` represent angles of the
/// region.
struct ExcludedRegion
{
uint16_t start;
uint16_t end;
};
Copy link
Collaborator

Choose a reason for hiding this comment

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

As the filter is not inherently a feature of the sensor, please move it to a class RingSectionFilter in its own header file.

Comment on lines +31 to +34
bool ring_section_filter;
std::map<int, std::vector<ExcludedRegion>>
excluded_ring_sectors; // Key holds the channel id, value holds excluded ring sectors belong to that
// channel
Copy link
Collaborator

Choose a reason for hiding this comment

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

As it is now, the bool and std::map could be assigned in invalid ways, e.g. ring_section_filter = false; excluded_ring_sectors = { /* not empty */ };. We should avoid such possibilities as much as possibe to make Nebula safer and more maintainable.
This would be cleaner as std::optional<RingSectionFilter>.

Comment on lines +186 to +197
/// @brief Checks if the point is inside invalid regions.
/// @param channel Channel id of the point.
/// @param azimuth Azimuth angle of the point.
/// @return True if the point is invalid, false otherwise.
bool check_excluded_point(const int & channel, const uint16_t & azimuth)
{
if (!sensor_configuration_->ring_section_filter) return false;
const auto & sectors = sensor_configuration_->excluded_ring_sectors[channel];
return std::any_of(sectors.begin(), sectors.end(), [azimuth](const auto & sector) {
return azimuth >= sector.start && azimuth <= sector.end;
});
}
Copy link
Collaborator

Choose a reason for hiding this comment

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

since the filter is not an inherent feature of the sensor, please move this to a class RingSectionFilter (and as @drwnz mentioned, precompute in the class's constructor).

Comment on lines +250 to +253
const bool is_not_excluded_point =
!check_excluded_point(corrections.laser_ring, azimuth_corrected);

if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) {
Copy link
Collaborator

Choose a reason for hiding this comment

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

To make clear to the reader that the existing FOV filtering (min_angle and max_angle) and the new RingBasedFilter are separate features, please refactor to:

Suggested change
const bool is_not_excluded_point =
!check_excluded_point(corrections.laser_ring, azimuth_corrected);
if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) {
const bool is_excluded_point =
check_excluded_point(corrections.laser_ring, azimuth_corrected);
if (is_excluded_point) {
continue;
}
if (is_within_min_max_angle || is_outside_max_min_angle) {

Comment on lines +207 to +210
const bool is_not_excluded_point =
!check_excluded_point(corrections.laser_ring, block.rotation);

if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) {
Copy link
Collaborator

Choose a reason for hiding this comment

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

To make clear to the reader that the existing FOV filtering (min_angle and max_angle) and the new RingBasedFilter are separate features, please refactor to:

Suggested change
const bool is_not_excluded_point =
!check_excluded_point(corrections.laser_ring, block.rotation);
if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) {
const bool is_excluded_point =
check_excluded_point(corrections.laser_ring, block.rotation);
if (is_excluded_point) {
continue;
}
if (is_within_min_max_angle || is_outside_max_min_angle) {

Comment on lines +271 to +274
const bool is_not_excluded_point =
!check_excluded_point(corrections.laser_ring, azimuth_corrected);

if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) {
Copy link
Collaborator

Choose a reason for hiding this comment

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

To make clear to the reader that the existing FOV filtering (min_angle and max_angle) and the new RingBasedFilter are separate features, please refactor to:

Suggested change
const bool is_not_excluded_point =
!check_excluded_point(corrections.laser_ring, azimuth_corrected);
if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) {
const bool is_excluded_point =
check_excluded_point(corrections.laser_ring, azimuth_corrected);
if (is_excluded_point) {
continue;
}
if (is_within_min_max_angle || is_outside_max_min_angle) {

@@ -19,13 +19,19 @@

<arg name="setup_sensor" default="True" description="Enable sensor setup on hw-driver."/>

<arg name="enable_ring_section_filter" default="false"/>
<arg name="excluded_ring_sectors"
default="[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]"/>
Copy link
Collaborator

Choose a reason for hiding this comment

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

As noted in README.md, I think specifying floats (35.00, 69.00 etc.) is more easily understandable to the user.

Also, please set the default to an emty filter. Instead, a `description=". Example: '[0, 3500, 6900], ...'" would be nice.

Comment on lines +287 to +289
// Add the ExcludedRegion to the map under the corresponding ring number
sensor_configuration.excluded_ring_sectors[ring_number].emplace_back(
drivers::ExcludedRegion{start, end});
Copy link
Collaborator

Choose a reason for hiding this comment

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

As noted in velodyne_common.hpp, it would be nicer (better separation of concerns) if the configuration contained a std::optional<RingBasedFilter> instead of bool ring_section_filter and excluded_ring_sectors.

- `enable_ring_section_filter` toggles a ring-based filter to remove points located within predefined angle ranges.
- Specify an excluded section using the format `[ring_id, start_angle, end_angle]`.
- Angles must be in degrees, scaled by a factor of 100. For example, represent `34.44` degrees as `3444`.
- It's possible to define multiple excluded regions for the same ring, allowing for versatile filtering configurations.
Copy link
Collaborator

Choose a reason for hiding this comment

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

"It's" sounds a bit informal, how about:

Suggested change
- It's possible to define multiple excluded regions for the same ring, allowing for versatile filtering configurations.
- It is possible to define multiple excluded regions for the same ring, allowing for versatile filtering configurations.

@tier4 tier4 deleted a comment from mojomex Jun 14, 2024
@mebasoglu
Copy link
Collaborator Author

Hello @drwnz @mojomex, unfortunately I couldn't take a look at the PR since your review. It seems we aren't able to work on this right now. I wonder if it's all right for you to continue with this issue?

@mojomex
Copy link
Collaborator

mojomex commented Jun 27, 2024

@mebasoglu As we want to implement something similar for Hesai sensors too, I think we can pick up where you left off. Not sure if it will happen this week, but definitely soon!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

Enhancement: Add Ring-Based Filter for Removing Reflected and Vehicle Points
6 participants