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

Not enough inliers found to optimize model coefficients (0)! #22

Open
ffent opened this issue Apr 8, 2021 · 3 comments
Open

Not enough inliers found to optimize model coefficients (0)! #22

ffent opened this issue Apr 8, 2021 · 3 comments
Labels
good first issue Good for newcomers

Comments

@ffent
Copy link

ffent commented Apr 8, 2021

Hi,

I'm trying to use the lidar_detector_node without any success. I tried different settings but getting the following error:

[ INFO] [1617898057.099646647]: Initialized lidar detector.
[ INFO] [1617898059.825417059]: Receiving lidar point clouds.
[pcl::SampleConsensusModelPlane::optimizeModelCoefficients] Not enough inliers found to optimize model coefficients (0)! Returning the same coefficients.
Ring too small, continue..
[ INFO] [1617898059.851282781]: Ignoring exceptions thrown by pcl in at least one frame.
[ INFO] [1617898059.851311459]: Publishing patterns.

I would be very grateful if you could give me any advises or more information on the different parameters of the config.yaml file.

@ffent ffent mentioned this issue Apr 9, 2021
@EaiPool
Copy link
Member

EaiPool commented Apr 9, 2021

finding a configuration that works can indeed be somewhat fiddly: the lidar detector has quite a few filters in a row, and something can go wrong at every step.

For general debugging here, I can recommend to turn visualise to true. The filtering and keypoint detection happens here, and an example of the debug visualization in use is this line here.
If the visualized pointcloud does not look like either the calibration board, or a scene which contains the calibration board, then something's going wrong, possibly already in an earlier step. You can add additional visualization to the other filtering steps, e.g. add
if (config.visualize) { visualize(cloud_without_ground_floor ); }
to line 378 here.

For specific debugging: for me, the pass through filter (lines 4-6) was the most critical step to get right: once I had that the rest was smooth sailing. What I did was start up RVIZ, let is visualize the pointcloud, and then select the "publish point" button in the top.
image
With that enabled (don't click on any point, just hover over them), you can find the x/y/z coordinates of any point, which in turn makes it easier to figure out what the filter region should be.
The x/y/z coordinate is given in the bottom:
image

let me know if this helps. The "debug" visualization of the filtering here could use some upgrades, so if you have any ideas or suggestions I am open to them. And you're of course also welcome to implement them yourself and put up a pull request ;)

@EaiPool EaiPool added the good first issue Good for newcomers label Apr 9, 2021
@ffent
Copy link
Author

ffent commented Apr 9, 2021

Thanks @EaiPool for your quick response and detailed debugging advises. However, the pass through filter seems not to be the problem (as shown by the point cloud below).

Point cloud after pass through filter (passthrough_cloud)

Screenshot from 2021-04-09 16-27-40

It seems like the ground floor filter deleted all points. However, after removing (skipping) the ground floor filter I'm getting the following error.

[pcl::SampleConsensusModel::getSamples] Can not select 0 unique points out of 0!
[pcl::RandomSampleConsensus::computeModel] No samples could be selected!
[pcl::SACSegmentation::segment] Error segmenting the model! No solution found.

Since the calibration board filtering (plane extraction) is working fine, as shown by the image below,

Point cloud after plane extraction (cloud_calibration_board)

Screenshot from 2021-04-09 16-44-53

it looks like the edge detection is unable to detect anything. So my question would be if you could please provide some further information on the parameters of the config.yaml file. To be more precise:

visualize: false
lidar_parameters:
    number_layers: 64
pass_through_filter: 
    -  {dim: "y", min: 3.0, max: 6.5} 
    -  {dim: "x", min: -2.0, max: 2.5}           
ground_floor_filter:                             
    distance_threshold: 0.1                                # What does the distance threshold define?
    axis: {x: 0.0, y: 0.0, z: 1.0}                                # Does this define the plane or a coordinate value?
    eps_angle: 0.55                                # What is this parameter for?
    max_iterations: 1000
    set_negative: true                                # What is this for?
    model_type: "sacmodel_perpendicular_plane"
    return_projected: false
calibration_board_filter:
    distance_threshold: 0.15
    axis: {x: 0.0, y: 0.0, z: 1.0}
    eps_angle: 0.55
    max_iterations: 250
    set_negative: false
    model_type: "sacmodel_parallel_plane"
    return_projected: true
circle_detection:
    distance_threshold: 0.03
    max_iterations: 1000
    min_radius: 0.06                             # Is this the minimum search radius or the min radius of the circle?
    max_radius: 0.1
    cluster_iterations: 100
    max_points_within_radius: 0
    radius_max_points: 0.03                      # Not sure what this radius defines.
cloud_edge_filter:
    threshold: 0.5
    radius: 0.0736                               # How is this value determined?
refinement:                                      
    refine: false                                 # Why 3 or 4 detentions?
    width: 0.24
    height: 0.24
    threshold_inlier: 0.02                       # How to interpret this threshold value?

I appreciate your help very much and would be very grateful if you could answer my questions above.

@EaiPool
Copy link
Member

EaiPool commented Apr 14, 2021

Each of those config items corresponds to a configuration option on the related pcl function, for example these lines configure this function. I will put links to the related function inside the configuration file to clear that up.

The 3D visualization of the board looks great though, so the pass through filter, ground_floor filter and calibration board filter seem to work nicely.
To comment on your other points:

circle_detection:
    distance_threshold: 0.03
    max_iterations: 1000
    min_radius: 0.06                   # Is this the minimum search radius or the min radius of the circle? 
                                       # It's the minimum radius of the circle
    max_radius: 0.1
    cluster_iterations: 100
    max_points_within_radius: 0
    radius_max_points: 0.03            # Not sure what this radius defines.
                                       # A detected circle (or, technically, circle center) is only considered a correct circle center if there are zero lidar points within this radius
cloud_edge_filter:
    threshold: 0.5
    radius: 0.0736                     # How is this value determined?
                                       # This should rougly correspond to the distance between two points on the calibration board. This is used to compute the edges of the board.
refinement:                                      
    refine: false                      # Why 3 or 4 detentions?
                                       # I'm not sure what you mean here
    width: 0.24
    height: 0.24
    threshold_inlier: 0.02             # How to interpret this threshold value?
                                       # The refinement stage processes the four detected circles as a whole, basically comparing it to the expected template of the calibration board. If any circle center differentiates more than this distance from the expected template position, the detection is considered incorrect.

The most important steps here are most likely the spacial resolution for the edge detector, and the min/max radius of the circles. The expected radius found by the circle detector will be slightly larger than the radius that you've given the circles in the calibration board by the way, because the lidar points don't follow the circle perfectly, but trace a rough outline of it on the surface of the calibration board.

Additionally, I would recommend you to try and visualize future steps in the process. does the edge detection step work, for instance?

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

No branches or pull requests

2 participants