Skip to content

Commit

Permalink
fix: lidar eval
Browse files Browse the repository at this point in the history
  • Loading branch information
YifuTao committed Sep 18, 2024
1 parent d7d933d commit 4505404
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 7 deletions.
11 changes: 8 additions & 3 deletions scripts/reconstruction_benchmark/lidar_cloud_eval.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,12 @@


def evaluate_lidar_cloud(
project_folder, lidar_cloud_folder_path, gt_folder_path, octomap_resolution=0.1, downsample_voxel_size=0.05
project_folder,
lidar_cloud_folder_path,
gt_octree_path,
gt_cloud_path,
octomap_resolution=0.1,
downsample_voxel_size=0.05,
):
input_cloud_bt_path = Path(project_folder) / "input_cloud.bt"
processPCDFolder(str(lidar_cloud_folder_path), octomap_resolution, str(input_cloud_bt_path))
Expand All @@ -20,9 +25,9 @@ def evaluate_lidar_cloud(
input_cloud_merged_path = Path(project_folder) / "input_cloud_merged.ply"
_ = merge_downsample_vilens_slam_clouds(lidar_cloud_folder_path, downsample_voxel_size, input_cloud_merged_path)
input_cloud_filtered_path = Path(project_folder) / "input_cloud_merged_filtered.ply"
removeUnknownPoints(str(input_cloud_merged_path), str(gt_cloud_bt_path), str(input_cloud_filtered_path))
removeUnknownPoints(str(input_cloud_merged_path), str(gt_octree_path), str(input_cloud_filtered_path))
input_cloud_np = np.asarray(o3d.io.read_point_cloud(str(input_cloud_filtered_path)).points)
gt_cloud_np = np.asarray(self.gt_cloud_merged.points)
gt_cloud_np = np.asarray(o3d.io.read_point_cloud(str(gt_cloud_path)).points)

print(get_recon_metrics(input_cloud_np, gt_cloud_np))
save_error_cloud(input_cloud_np, gt_cloud_np, str(Path(project_folder) / "input_error.ply"))
13 changes: 9 additions & 4 deletions scripts/reconstruction_benchmark/main.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
from pathlib import Path

import numpy as np
from lidar_cloud_eval import evaluate_lidar_cloud

from oxford_spires_utils.bash_command import print_with_colour
from oxford_spires_utils.point_cloud import merge_downsample_vilens_slam_clouds
from oxford_spires_utils.utils import convert_e57_folder_to_pcd_folder
from oxford_spires_utils.utils import convert_e57_folder_to_pcd_folder, transform_pcd_folder
from spires_cpp import convertOctreeToPointCloud, processPCDFolder


Expand All @@ -20,11 +21,11 @@ def __init__(self, project_folder):
# TODO: check lidar cloud folder has viewpoints and is pcd, check gt folder is pcd, check image folder is jpg/png
self.octomap_resolution = 0.1
self.cloud_downsample_voxel_size = 0.05
self.gt_octree_path = self.output_folder / "gt_cloud.bt"
self.gt_cloud_merged_path = self.output_folder / "gt_cloud_merged.ply"

def process_gt_cloud(self):
print_with_colour("Creating Octree and merged cloud from ground truth clouds")
self.gt_octree_path = self.output_folder / "gt_cloud.bt"
self.gt_cloud_merged_path = self.output_folder / "gt_cloud_merged.ply"
processPCDFolder(str(self.gt_individual_folder), self.octomap_resolution, str(self.gt_octree_path))
gt_cloud_free_path = str(Path(self.gt_octree_path).with_name(f"{Path(self.gt_octree_path).stem}_free.pcd"))
gt_cloud_occ_path = str(Path(self.gt_octree_path).with_name(f"{Path(self.gt_octree_path).stem}_occ.pcd"))
Expand All @@ -35,7 +36,11 @@ def process_gt_cloud(self):

def evaluate_lidar_clouds(self):
evaluate_lidar_cloud(
self.output_folder, self.individual_clouds_folder, self.gt_individual_folder, self.octomap_resolution
self.output_folder,
self.individual_clouds_folder,
self.gt_octree_path,
self.gt_cloud_merged_path,
self.octomap_resolution,
)

def tranform_lidar_clouds(self, transform_matrix_path=None):
Expand Down

0 comments on commit 4505404

Please sign in to comment.