libOpenDRIVE
libOpenDRIVE copied to clipboard
OBJ export - only reference line & roadmarks
Hi,
Many thanks for your great work and this great tool !
Is there a way to export only reference lines and roadmarks as .OBJ, without the underlying roads mesh ? It is possible to hide the roads mesh in the View but it would be very interesting to do so during export as well.
Many thanks in advance for your time and effort,
Best regards,
Henry
Hi Henry, appreciate it!
You should be able to generate a mesh containing only the roadmarks using this library:
odr::OpenDriveMap odr_map("test.xodr");
const double eps = 0.1;
odr::Mesh3D roadmarks_mesh;
for (odr::Road road : odr_map.get_roads())
{
for (odr::LaneSection lanesection : road.get_lanesections())
{
const double s_start = lanesection.s0;
const double s_end = road.get_lanesection_end(lanesection);
for (odr::Lane lane : lanesection.get_lanes())
{
auto roadmarks = lane.get_roadmarks(s_start, s_end);
for (const auto& roadmark : roadmarks)
{
auto roadmark_mesh = road.get_roadmark_mesh(lane, roadmark, eps);
roadmarks_mesh.add_mesh(roadmark_mesh);
}
}
}
}
std::ofstream out_file;
out_file.open("out.obj");
out_file << roadmarks_mesh.get_obj() << std::endl;
out_file.close();
Thanks for pointing me to this library, I'll try it out !