Closed NewThinker-Jeffrey closed 1 month ago
Can you add a qualitative and quantitative comparison of the estimation results before and after your PR?
Can you add a qualitative and quantitative comparison of the estimation results before and after your PR?
Of course, let me make it clear.
I tested with this image from #334 . The ground truth coordinate for the left top corner of the first tag is (10,10), as shown in #334 :
With the current master branch, the estimated coordinates of that corner under different settings are:
(1). refine_edges=false, quad_decimate=1
: (9.997555, 10.000000)
(2). refine_edges=false, quad_decimate=2
: (9.500000, 9.500000)
(3). refine_edges=true, quad_decimate=1
: (10.130014, 9.875005)
(4). refine_edges=true, quad_decimate=2
: (9.875000, 9.875005)
(This is the default setting of Apriltag, and the result coincides with that in #334 )
As we can see,
(0.5, 0.5)
is present due to the inconsistent coordinate conventions used in the code, which can be fixed by some small modifications here and hererefine_edges
is enabled (setting (3) and (4)), extra error can be introduced which is mainly caused by the discrete coordinates used when retrieving grayscale values from the input image. This can be addressed by applying continuous coordinates and bilinear interpolation.With the modified code (this PR), the estimated coordinates under different settings are all close to the groundtruth (10,10):
(1). refine_edges=false, quad_decimate=1
: (9.997555, 10.000000)
(2). refine_edges=false, quad_decimate=2
: (10.000000, 10.000000)
(3). refine_edges=true, quad_decimate=1
: (9.999912, 10.000005)
(4). refine_edges=true, quad_decimate=2
: (10.000000, 10.000005)
Thanks to this, I found that I broke the tests with https://github.com/AprilRobotics/apriltag/pull/327 when I tried to make them less flaky. The test compares the pixel coordinates and should trigger an error if the absolute error is larger than 0.1 pixels: https://github.com/AprilRobotics/apriltag/blob/3806edf38ac4400153677e510c9f9dcb81f472c8/test/test_detection.c#L47-L54
Setting:
td->quad_decimate = 2;
td->refine_edges = false;
in the tests should therefore have triggered this when running ctest --test-dir test/
.
I fixed the test on Ubuntu in https://github.com/AprilRobotics/apriltag/pull/348. But on other OSes, the results are slightly different and therefore have a small discrepancy to the reference values:
Got:
0, (357.3853 346.3749), (373.2110 347.5041), (373.4671 329.2181), (357.2913 328.1352)
Expected:
0, (357.4018 346.3447), (373.2110 347.5034), (373.4671 329.2181), (357.1758 328.1275)
and I am wondering if this may be caused by rounding effects and fixed by this PR.
I changed the tests to not decimate quads or refine edges:
td->quad_decimate = 1;
td->refine_edges = false;
and now get identical (accurate up to 0.001 pixels) results across OSes, which suggests that decimation and refinement are causing unreliable detections.
While refine_edges=false, quad_decimate=1
is supposed to give the true stable solution, I get different results for decimation and refinement
td->quad_decimate = 2;
td->refine_edges = true;
after applying your first commit.
Can you show with debug results from the test images, that this PR should produce the same quads, just better refined?
Can you show with debug results from the test images, that this PR should produce the same quads, just better refined?
I'm not entirely sure what you mean by "debug results from the test images". I have simply enabled td->debug
and tested the setting refine_edges=true, quad_decimate=2
again with the image mentioned above. The debug output has been packed into a .zip file, please refer to the attachment.
apriltag_debug.zip
Update:
I think these might be what you want: (refine_edges=true, quad_decimate=2
)
(test image: apriltag/test/data/34139872896_defdb2f8d9_c.jpg)
More results: apriltag-pr346-master-compare.zip
It can be observed that master and this pr produce slightly different coordinates for the tag corners. However it's hard to tell which version is better than the other according to these results only, because the ground truths for real world images are unknown. Anyway, theoretically speaking, using continuous coordinates (with interpolation) to retrieve pixel values, as done in this pr, can generate more accurate edge points, and the test with the ideal input image (from #334 ) , where ground truth is available, does show that this pr can produce nearly perfect estimation for the corners' coordinates.
Can you squash your commits together again?
I'll squash the two commits into one after you confirm whether we should merge the if/else blocks mentioned above.
It can be observed that master and this pr produce slightly different coordinates for the tag corners.
Thanks for the comparison. The results are indeed very close.
However it's hard to tell which version is better than the other according to these results only, because the ground truths for real world images are unknown.
I selected real images since some processing steps, such as the edge refinement, will have more noticeable effects on noisy real images than clean synthetic images.
Anyway, theoretically speaking, using continuous coordinates (with interpolation) to retrieve pixel values, as done in this pr, can generate more accurate edge points, and the test with the ideal input image (from #334 ) , where ground truth is available, does show that this pr can produce nearly perfect estimation for the corners' coordinates.
I originally added the test images to see if a PR would change the estimated quads. For a performance evaluation of which method is better, we would need to manually label these images and extract ground truth corner coordinates. Alternatively, we could render synthetic images for the ground truth coordinates and add blur, noise and other effects to see how a change affects the performance.
@christian-rauch Hi, I have squashed the previous commits. Please let me know if any further modifications are needed.
fixes #334, fixes #345
is not a nice commit message title. The commit message title should summarise what the change is and does and the commit message body should have the details. Your commit has quite a few functional changes. Documenting the effect and why this is done is therefore important. Your commit message body contains two bullet points. Is it possible to split this one commit into two separate functional changes, i.e. one that fixes the image coordinate conventions and another one that touches the bilinear interpolation?
I recently fixed the tests to work across OSes with no decimation. Can you rebase your PR to make sure that it does not break the tests without decimation? Then, we probably need a test for the results with decimation to make sure that results with decimation are close to the ones without decimation and that the output does not change in future.
Hi christian-rauch,
Is it possible to split this one commit into two separate functional changes, i.e. one that fixes the image coordinate conventions and another one that touches the bilinear interpolation?
Yes, it's better to split the commit into two.
I think we should update the doc file apriltag_detect.docstring
or README.md
to add an explicit explanation to the image coordinate convention somewhere. For example in apriltag_detect.docstring
:
- center: pixel coordinates of the center of each detection. NOTE: Please be
cautious regarding the image coordinate convention. Here, we define (0,0) as
the left-top corner (not the center point) of the left-top-most pixel.
- lb-rb-rt-lt: pixel coordinates of the 4 corners of each detection. The order
is left-bottom, right-bottom, right-top, left-top
Or maybe you have better suggestions?
Thank you for splitting this. I think the purpose of the diffs are much easier to understand.
Regarding the commits message: I think the title is far too long and the message body also should have line breaks. If you look at an individual commit, e.g. 5666602, then ideally the title fits into the first line without line breaks.
Modified as you suggested, please see the new commits.
@christian-rauch @mkrogius
Hi, I noticed that this PR is still not merged. I might need to introduce some unrelated features to this branch in the coming weeks. If possible, could you please review the changes and consider merging them if you find them beneficial? Your feedback and guidance on this matter would be invaluable. Thank you for your attention to this request.
As said, I am fine with these changes now. I would still like @mkrogius to have a look at this.
@NewThinker-Jeffrey What is your deadline on this? You can create a new branch from this and start working there. You do not have to (and you shouldn't) push new changes to this PR.
As said, I am fine with these changes now. I would still like @mkrogius to have a look at this.
@NewThinker-Jeffrey What is your deadline on this? You can create a new branch from this and start working there. You do not have to (and you shouldn't) push new changes to this PR.
I understand that and won't push my new changes to this branch before the PR finished.
I am going to merge this now to not delay this further and potentially causing merge conflicts later.
fix refine_edges() and the coordinates recovery when quad_decimate > 1 (fixes #334, fixes #345)