maliput_integration
maliput_to_obj application

Generating OBJ files

maliput_to_obj application allows to create an OBJ file from a maliput::api::RoadGeometry. The backends that can be selected to build the RoadGeometry are maliput_malidrive, maliput_multilane and maliput_dragway.

The application possesses flags to modify the OBJ mesh output. For example: the maximum size of a grid unit or whether to draw the elevation boundaries of lanes.

--max_grid_unit
--min_grid_resolution
--draw_elevation_bounds
--simplify_mesh_threshold

Depending on the maliput backend that is selected different flags related to the RoadGeometry building process will be active.

A description of all the available flags can be seen by running maliput_to_obj --help.

Note: This application consumes methods that are publicly provided by maliput package to generate OBJ files, so please refer to maliput::utility::GenerateObjFile() for further information if needed.

Let's use the default values of the OBJ builder configuration flags except for --max_grid_unit and --draw_elevation_bounds, which will be disabled to better see the meshes`.

$ maliput_to_obj --max_grid_unit=1 --draw_elevation_bounds=false --dirpath="." --file_name_root=maliput_to_obj_tutorial

As result two files are expected to be created in the selected dirpath:

  • maliput_to_obj_tutorial.obj
  • maliput_to_obj_tutorial.mtl

Then we can open maliput_to_obj_tutorial.obj using any free software for visualizing obj files, for example using MeshLab.

$ meshlab maliput_to_obj_tutorial.obj

Optional: Create URDF file.

An .urdf file can also be created when the --urdf flag is passed:

$ maliput_to_obj --max_grid_unit=1 --draw_elevation_bounds=false --dirpath="." --file_name_root=maliput_to_obj_tutorial --urdf

Therefore, a maliput_to_obj_tutorial.urdf file will be created at the same location than the other files.

Using maliput_malidrive backend

$ maliput_to_obj --maliput_backend=malidrive --xodr_file_path=TShapeRoad.xodr --omit_nondrivable_lanes=true --max_grid_unit=1 --draw_elevation_bounds=false --dirpath="." --file_name_root=maliput_to_obj_tutorial

Output:

[INFO] Loading road network using malidrive backend implementation...
[INFO] RoadNetwork loaded successfully.
[INFO] OBJ files location: /home/maliput_ws.
[INFO] Generating OBJ...
[INFO] OBJ creation has finished.

Mesh visualization using MeshLab:

$ meshlab maliput_to_obj_tutorial.obj

Using maliput_multilane backend

Similarly, maliput_multilane can be used.

$ maliput_to_obj --maliput_backend=multilane --yaml_file=2x2_intersection.yaml --max_grid_unit=1 --draw_elevation_bounds=false --dirpath="." --file_name_root=maliput_to_obj_tutorial

Output:

[INFO] Loading road network using multilane backend implementation...
[INFO] RoadNetwork loaded successfully.
[INFO] OBJ files location: /home/maliput_ws.
[INFO] Generating OBJ...
[INFO] OBJ creation has finished.

Mesh visualization using MeshLab:

$ meshlab maliput_to_obj_tutorial.obj

Using maliput_dragway backend

Similarly, maliput_dragway can be used.

$ maliput_to_obj --maliput_backend=dragway --num_lanes=3 --length=5 --lane_width=3 --shoulder_width=0.5 --max_grid_unit=1 --draw_elevation_bounds=false --dirpath="." --file_name_root=maliput_to_obj_tutorial

Output:

[INFO] Loading road network using dragway backend implementation...
[INFO] RoadNetwork loaded successfully.
[INFO] OBJ files location: /home/maliput_ws.
[INFO] Generating OBJ...
[INFO] OBJ creation has finished.

Mesh visualization using MeshLab:

$ meshlab maliput_to_obj_tutorial.obj

More available options

As mentioned before, maliput_to_obj application has several arguments that can be used. All of them can be accessed by running maliput_to_obj --help.

Use --log_level to set the log output See possible values at maliput::common::logger::level. By default set to unchanged.