(Intensity) OctoMap Python Bindings¶
In addition to the SOGMM work, we also provide python bindings over the widely used OctoMap work [1]. These python bindings were created for performance comparison with SOGMM. Thus, we made use of the ColorOcTree
class from the original codebase. Our fork of the OctoMap repository is included in the dry
workspace.
The setup for input data is the same as in the preceding tutorial.
If you use these bindings in your work, please cite the OctoMap paper [1].
Creating the OctoMap Model¶
Import the ColorTree
class from octomap_py
and specify the input data.
%matplotlib inline
import numpy as np
import open3d as o3d
from sogmm_py.utils import read_log_trajectory, o3d_to_np, np_to_o3d
from sogmm_py.vis_open3d import VisOpen3D
from octomap_py import ColorOcTree
frame = 1763
datasetname = 'lounge'
pcld_gt = o3d.io.read_point_cloud('./gira3d-tutorial-data/pcd_' +
str(datasetname) +
'_' + str(frame) +
'_decimate_1_0.pcd', format='pcd')
pcld_gt_np = o3d_to_np(pcld_gt)
traj = read_log_trajectory('./gira3d-tutorial-data/' +
str(datasetname) + '-traj.log')
pcld_pose = traj[frame].pose
K = np.eye(3)
K[0, 0] = 525.0
K[1, 1] = 525.0
K[0, 2] = 319.5
K[1, 2] = 239.5
W = (int)(640)
H = (int)(480)
Specify the minimum leaf size for ColorOcTree
.
res = 0.02 # let us go with 2cm for this tutorial
model = ColorOcTree(res)
Load the ground truth point cloud into the OctoMap model and update the cells.
model.insert_color_occ_points(pcld_gt_np)
model.update_inner_occupancy()
Inference for Intensity Image¶
OctoMap is not a generative model (in contrast to NDTMap and SOGMM). We directly query the available points in this case.
recon_pcld = np.zeros(pcld_gt_np.shape)
recon_pcld[:, 0:3] = pcld_gt_np[:, 0:3] # we are constructing intensity image on gt 3D points
regressed_intensities = model.get_color_at_points(pcld_gt_np[:, 0:3])
recon_pcld[:, 3] = np.squeeze(regressed_intensities)
vis = VisOpen3D(visible=True)
vis.visualize_pcld(np_to_o3d(recon_pcld), pcld_pose, K, W, H)
vis.render()
del vis
Dense Sampling for 3D Point Cloud Reconstruction¶
We get the lowest level (i.e. highest fidelity) from ColorOcTree
.
resampled_pcld = model.get_color_occ_points()
vis = VisOpen3D(visible=True)
vis.visualize_pcld(np_to_o3d(resampled_pcld), pcld_pose, K, W, H)
vis.render()
del vis
Performance Measures¶
Same performance measures are computed as in the SOGMM case.
from sogmm_py.utils import calculate_depth_metrics, calculate_color_metrics
fsc, pre, re, rm, rs = calculate_depth_metrics(pcld_gt, np_to_o3d(resampled_pcld))
print("fscore %f precision %f recall %f recon. mean %f recon. std. dev. %f" % (fsc, pre, re, rm, rs))
from sogmm_py.utils import ImageUtils
iu = ImageUtils(K) # image manipulation utility
_, gt_g = iu.pcld_wf_to_imgs(pcld_pose, pcld_gt_np) # project gt pcld on camera
if np.isnan(gt_g).any():
gt_g = np.nan_to_num(gt_g)
_, pr_g = iu.pcld_wf_to_imgs(pcld_pose, recon_pcld) # project recon pcld on camera
if np.isnan(pr_g).any():
pr_g = np.nan_to_num(pr_g)
psnr, ssim = calculate_color_metrics(gt_g, pr_g) # compare the intensity images
print("psnr %f ssim %f" % (psnr, ssim))
fscore 0.610435 precision 0.526697 recall 0.725834 recon. mean 0.009577 recon. std. dev. 0.002803 psnr 22.993741 ssim 0.759709
# computing memory usage
model.write('temp.ot')
import os
mem_bytes = os.path.getsize('temp.ot')
print('memory %d bytes' % (mem_bytes))
!rm temp.ot
memory 117715 bytes
References¶
[1] A. Hornung, K. M. Wurm, M. Bennewitz et al., “OctoMap: An efficient probabilistic 3D mapping framework based on octrees,” Autonomous Robots, vol. 34, no. 3, pp. 189–206, Apr. 2013