libOpenDRIVE
libOpenDRIVE copied to clipboard
Can't access to the ParamPoly3 variables.
Thank you for the great work for all of the contributors here!
I tried to access the Parampoly3 members but I think the data was not stored in the map reading step.
When I access Parampoly3, I used the code line below.
aU = road->ref_line->s0_to_geometry[0.0]->aU;
Thanks. Appreciate it! The ParamPoly3 parameters (aU, bU, ...) get stored when parsing. But note that if pRange_normalized==False
the parameters get modified. In OpenDrive you can specify if p
in the ParamPoly3 equation goes from [0;1]
(normalized) or [0;arc length]
. In the non-normalized case I "normalize" the parameter to not have two different calculation models.
https://github.com/grepthat/libOpenDRIVE/blob/90dd05b89e4ba157badb2a7f8ec079fcba260252/src/Geometries/ParamPoly3.cpp#L29
But I'm not sure what you mean by the data is not there? Is aU=0 or some random value? You might also want to check if there actually is a ParamPoly3
geometry at s==0.0, e.g.:
auto s0_geom_iter = road->ref_line->s0_to_geometry->find(0.0);
if (s0_geom_iter != road->ref_line->s0_to_geometry.end())
{
odr::ParamPoly3* param_poly3_ptr = std::dynamic_cast<odr::ParamPoly3*>(s0_geom_iter->second.get());
if (param_poly3_ptr)
aU = param_poly3_ptr->aU;
}
closing this, seems to be resolved?