-
Notifications
You must be signed in to change notification settings - Fork 661
Importing Data into OctoMap
You can build 3D maps from point cloud data (e.g., laser scans, stereo, RGB-D (Kinect)...) in the code using the insertScan(...) functions in an octree map.
Other methods of importing or converting data are detailed below.
Plain-text laser scan data can be imported from the following file format:
NODE x y z roll pitch yaw
x y z
x y z
[...]
NODE x y z roll pitch yaw
x y z
[...]
The keyword NODE
is followed by the 6D pose of the laser origin of the 3D scan (coordinates are regarded as SI units: meter for translation & rad for angles. x points forward, y left, z up. roll, pitch, and yaw angles are around the axes x, y, z respectively). After a NODE
-line, the laser endpoints of the scan originating at that scan node are listed as 3D points, in the coordinate frame of the scan node. The next NODE
keyword specifies the start of a new 3D scan. Lines starting with '#' or empty lines are ignored.
Our tool "log2graph" converts these plain-text log files into a binary scan graph file, which can be directly opened and converted in the viewer "octovis", or converted to an octree map from the command line with "graph2tree".
You can create an OctoMap file from a variety of 3D mesh formats (3DS, VRML, OBJ ...) by first voxelizing them with binvox. First, obtain the latest version from the author's homepage (the binaries support more mesh formats).
VRML97 (2.0) data seems to work best in binvox. If your data is already in that format (and metric), skip forward. Google Sketchup for example is not able to export into a working VRML 2.0 file (the units are all in inches). This, and wrong normals often cause problems in voxelization.
Useful workflows for some 3D editors:
- Export to a 3DS file. Make sure to set "Units" to "Meters" in the export options.
- Open Blender and be sure to delete the little cube which blender adds by default.
- Import the 3DS file from step 1 into Blender. Disable the "Size Constraint" scaling option by setting the value to 0 in the import dialog.
- Blender >= 2.50 only: In the import dialog, set the forward axis to "Y" and the up axis to "Z".
- Continue with the instructions for your Blender version below.
- The Blender importer cannot deal with components, so you have to break all components first: Mark all objects in the scene by pressing Ctrl+A, right click on an object and select "explode".
- Export to a Collada (.dae) file.
- Open Blender and be sure to delete the little cube which blender adds by default.
- Import the Collada file from step 1 into Blender (Blender <= 2.49: Use the COLLADA 1.4 importer).
- Scale the scene around the coordinate system origin by 0.0254 to convert the dimensions from inches to meters.
- Continue with the instructions for Blender below.
- Export to VRML97 (.wrl) and deactivate the axis swap option in the export dialog.
- Export to X3D Extensible 3D. In the export options, set the forward axis to "Y" and the up axis to "Z".
- Convert the X3D file to VRML97 by applying the XML stylesheet available at http://www.web3d.org/x3d/content/X3dToVrml97.xslt to the X3D file (e.g. using xsltproc command line tool).
Run binvox on the exported VRML file. Recommended options:
- -e exact carving gives best results, but results e.g. in hollow walls (no room for compression in the octree)
- otherwise try a combination of -c and / or -v. This might or might not work for some meshes
- -fit gives the smallest bounding box fit
- -d : Number of voxels for the longest cube dimension. You need to tweak this number so that the final map (after octree creation) has the desired resolution.
The result is a ".binvox" file. You can verify the overall correctness of scale with the output "bounding box: [...]" (should be correct in meters).
With binvox2bt you can create a binary (occupied / free, remainder is unknown) octree. The option --mark-free
will mark all freespace, otherwise it's "unknown". binvox2bt will also output the smallest voxel resolution, so you might have to go back to the previous step to adjust . Setting the bounding box with --bb xmin ymin zmin xmax ymax zmax
to the bounding box printed by the binvox tool (extended by a small margin) reduces the size of the resulting binary tree. Verify the resulting .bt file in octovis.
After converting your 3D data to a binvox file, you can create an Octree map from it by running our tool "binvox2bt".
(Authors: Stefan Osswald & Armin Hornung)