Spiral geometries may be not correctly computed
MatteoRagni opened this issue · 6 comments
RTron version: 1.3.0
When validating an OpenDRIVE file with several "spiral" geometry definitions, several warnings and errors are raised. These errors are saved to the 02_opendrive_evaluator_report.json
file, and are of type GapBetweenPlanViewGeometryElements
. Here is an example of such an error:
{
"type": "GapBetweenPlanViewGeometryElements",
"info": "Geometry elements contain a gap from Vector2D(x=64.29300909560088, y=197.04569937574584) to Vector2D(x=64.28923043599997, y=197.03699148) with an euclidean distance of 0.00949240310457702 above the warning tolerance of 0.001.",
"location": "Road: roadId=1",
"incidentSeverity": "WARNING",
"wasFixed": false,
"infoValues": {
},
"messageSeverity": "WARNING"
}
These errors indicate that between two consecutive spirals of a single road, a gap of the indicated length exists. When visualizing the OpenDRIVE file in question with other tools (such as odrviewer.io), however, no such gap exists.
It is possible that the values along spirals are not correctly computed, and therefore the resulting gaps are incorrectly detected.
Can you please provide a small test dataset with which we can replicate the problem?
Yes we will provide a test dataset to try the spiral implementation. Do you have preferences about the format?
We added two unit tests that follow the ASAM example dataset Ex_Line-Spiral-Arc.xodr
to test the spiral implementation.
First spiral at s=1.0000000000000000e+02
:
Second spiral at s=1.5999999146329435e+02
:
For these cases, rtron's spiral implementation correctly returns the position of the succeeding geometry at an accuracy of around 1E-6
.
Can you double-check, if you can also reproduce these cases?
Any format should be fine, but I suggest starting with a spiral segment in the coordinate origin.
Thanks for the reply (and for your awesome work on rtron). We found the spiral artifacts on an OpenDRIVE that unfortunately cannot be shared publicly. We tested the geometrical representation of the same OpenDRIVE via 4 different independent spirals implementations. All the images shows the same road.
-
Internal implementation (sampling at 0.01 m, same results with higher sampling distance):
-
odrview.io (online) implementation (sampling at 0.01 - Details High):
-
rtron 1.3.0 cityGML output visualized via FZK Viewer (Generation with
--plan-view-geometry-distance-tolerance = 5m
to actually have an output file to visualize)
I'm attaching a possible testing database. My personal suspect is that the geometry of the spiral is fine, but the problem is in the selection of the actual geometry in the list of spirals that represent the full reference line. The artifacts in the CityGML is very similar to something I already seen in the past while writing meshing algorithms for OpenDRIVE, and in my previous experience it was due to a bug in the lookup table that selected the spiral in a list of spirals, given the curvilinear abscissa. Hopefully, the attached database will try to test also this part.
The dataset has been shared with @beneschwab, since it cannot be shared directly here (json files are not supported).
Thank you for reporting this issue! I think that I found the reason and was able to fix it:
It was a bug in the Fresnel integral implementation, as the parameter t
instead of u
was handed to the polynomial function evaluation:
rtron/rtron-math/src/main/kotlin/io/rtron/math/analysis/Fresnel.kt
Lines 62 to 63 in 6daa213
Since rtron has not been exposed to many spirals yet, this bug has not been revealed before.
Can you double-check if the develop branch solves the issue for you?
I also ran some experiments using your testing dataset: The end of each spiral is followed by the start of the succeeding spiral with a tolerance of 1.5E-8
.
develop (commit 6daa213) seems to fix the issue.
Thanks! Closing.