Skip to content

Commit

Permalink
IJRR paper submission (#13)
Browse files Browse the repository at this point in the history
  • Loading branch information
YifuTao authored Oct 28, 2024
2 parents e8f7746 + 5371fe9 commit 736f941
Show file tree
Hide file tree
Showing 14 changed files with 748 additions and 174 deletions.
14 changes: 14 additions & 0 deletions .docker/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -122,9 +122,23 @@ RUN git clone https://github.com/colmap/colmap.git --branch 3.8 ${HOME_DIR}/colm
####################

FROM colmap as nerfstudio
ARG NERFSTUDIO_VERSION=v1.1.4
RUN pip install --no-cache-dir --upgrade pip
RUN pip install --no-cache-dir torch==2.1.2+cu118 torchvision==0.16.2+cu118 'numpy<2.0.0' --extra-index-url https://download.pytorch.org/whl/cu118
RUN TCNN_CUDA_ARCHITECTURES="${CUDA_ARCHITECTURES}" pip install --no-cache-dir "git+https://github.com/NVlabs/tiny-cuda-nn.git@b3473c81396fe927293bdfd5a6be32df8769927c#subdirectory=bindings/torch"
RUN git clone https://github.com/nerfstudio-project/nerfstudio.git --branch ${NERFSTUDIO_VERSION} ${HOME_DIR}/nerfstudio &&\
cd ${HOME_DIR}/nerfstudio &&\
pip install -e .

FROM colmap as sdfstudio
ARG SDFSTUDIO_COMMIT=370902a
RUN pip install --no-cache-dir --upgrade pip
RUN pip install torch==1.12.1+cu113 torchvision==0.13.1+cu113 -f https://download.pytorch.org/whl/torch_stable.html
RUN TCNN_CUDA_ARCHITECTURES="${CUDA_ARCHITECTURES}" pip install --no-cache-dir "git+https://github.com/NVlabs/tiny-cuda-nn.git@b3473c81396fe927293bdfd5a6be32df8769927c#subdirectory=bindings/torch"
RUN git clone https://github.com/autonomousvision/sdfstudio.git ${HOME_DIR}/sdfstudio &&\
cd ${HOME_DIR}/sdfstudio &&\
git checkout ${SDFSTUDIO_COMMIT} &&\
pip install -e .

####################
# Deployment image #
Expand Down
13 changes: 13 additions & 0 deletions config/recon_benchmark.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
reconstruction_benchmark:
project_folder: "/home/docker_dev/oxford_spires_dataset/data/2024-03-13-observatory-quarter-01"
gt_folder: "/home/docker_dev/oxford_spires_dataset/data/ground_truth_cloud/observatory-quarter"

run_gt_cloud_processing: True
run_lidar_cloud_processing: True
run_lidar_cloud_evaluation: True
run_colmap: True
run_colmap_sim3: True
run_mvs: True
run_mvs_evaluation: True
run_nerfstudio: True
run_novel_view_synthesis_only: True
56 changes: 49 additions & 7 deletions oxford_spires_utils/eval.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
import logging
from pathlib import Path

import matplotlib.pyplot as plt
Expand All @@ -6,10 +7,12 @@
from matplotlib.colors import LinearSegmentedColormap
from scipy.spatial import cKDTree as KDTree

logger = logging.getLogger(__name__)


def compute_p2p_distance(query_cloud: np.ndarray, reference_cloud: np.ndarray):
ref_kd_tree = KDTree(reference_cloud)
distances, _ = ref_kd_tree.query(query_cloud)
distances, _ = ref_kd_tree.query(query_cloud, workers=-1)
return distances


Expand All @@ -21,26 +24,63 @@ def get_recon_metrics(
):
assert isinstance(input_cloud, np.ndarray) and isinstance(gt_cloud, np.ndarray)
assert input_cloud.shape[1] == 3 and gt_cloud.shape[1] == 3
print("Computing Accuracy and Precision ...")
logger.info(f"Computing Accuracy and Precision ({precision_threshold}) ...")
distances = compute_p2p_distance(input_cloud, gt_cloud)
accuracy = np.mean(distances)
precision = np.sum(distances < precision_threshold) / len(distances)

print("Computing Completeness and Recall ...")
logger.info(f"Computing Completeness and Recall ({recall_threshold}) ...")
distances = compute_p2p_distance(gt_cloud, input_cloud)
completeness = np.mean(distances)
recall = np.sum(distances < recall_threshold) / len(distances)
f1_score = 2 * (precision * recall) / (precision + recall)

print("Done!")
return {
results = {
"accuracy": accuracy,
"precision": precision,
"completeness": completeness,
"recall": recall,
"f1_score": f1_score,
}
return results


def save_error_cloud(input_cloud: np.ndarray, reference_cloud: np.ndarray, save_path, cmap="bgyr"):
def get_recon_metrics_multi_thresholds(
input_cloud: np.ndarray, gt_cloud: np.ndarray, thresholds: list = [0.02, 0.05, 0.1], max_distance=2.0
):
assert isinstance(input_cloud, np.ndarray) and isinstance(gt_cloud, np.ndarray)
assert input_cloud.shape[1] == 3 and gt_cloud.shape[1] == 3
results = []

logger.info("Computing Accuracy and Precision ...")
input_to_gt_dist = compute_p2p_distance(input_cloud, gt_cloud)
input_to_gt_dist = input_to_gt_dist[input_to_gt_dist <= max_distance]
accuracy = np.mean(input_to_gt_dist)

logger.info("Computing Completeness and Recall ...")
gt_to_input_dist = compute_p2p_distance(gt_cloud, input_cloud)
gt_to_input_dist = gt_to_input_dist[gt_to_input_dist <= max_distance]
completeness = np.mean(gt_to_input_dist)

logger.info(f"Accuracy: {accuracy:.4f}, Completeness: {completeness:.4f}")
results.append({"accuracy": accuracy, "completeness": completeness})
for threshold in thresholds:
precision = np.sum(input_to_gt_dist < threshold) / len(input_to_gt_dist)
recall = np.sum(gt_to_input_dist < threshold) / len(gt_to_input_dist)
f1_score = 2 * (precision * recall) / (precision + recall)
results.append(
{
"threshold": threshold,
"precision": precision,
"recall": recall,
"f1_score": f1_score,
}
)
logger.info(f"threshold {threshold} m, precision: {precision:.4f}, recall: {recall:.4f}, f1: {f1_score:.4f}")
return results


def save_error_cloud(input_cloud: np.ndarray, reference_cloud: np.ndarray, save_path, cmap="bgyr", max_distance=2.0):
def get_BGYR_colourmap():
colours = [
(0, 0, 255), # Blue
Expand All @@ -56,6 +96,8 @@ def get_BGYR_colourmap():
return cmap

distances = compute_p2p_distance(input_cloud, reference_cloud)
input_cloud = input_cloud[distances <= max_distance]
distances = distances[distances <= max_distance]
distances = np.clip(distances, 0, 1)
if cmap == "bgyr":
cmap = get_BGYR_colourmap()
Expand All @@ -67,7 +109,7 @@ def get_BGYR_colourmap():
test_cloud.points = o3d.utility.Vector3dVector(input_cloud)
test_cloud.colors = o3d.utility.Vector3dVector(distances_cmap[:, :3])
o3d.io.write_point_cloud(save_path, test_cloud)
print(f"Error cloud saved to {save_path}")
logger.info(f"diff cloud saved to {save_path}")


if __name__ == "__main__":
Expand Down
13 changes: 13 additions & 0 deletions oxford_spires_utils/point_cloud.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
import logging
from pathlib import Path

import numpy as np
Expand All @@ -9,6 +10,8 @@

from oxford_spires_utils.se3 import is_se3_matrix, xyz_quat_xyzw_to_se3_matrix

logger = logging.getLogger(__name__)


def transform_3d_cloud(cloud_np, transform_matrix):
"""Apply a transformation to the point cloud."""
Expand Down Expand Up @@ -174,3 +177,13 @@ def convert_e57_to_pcd(e57_file_path, pcd_file_path, check_output=True, pcd_lib=
if has_colour:
colours_np = np.array(saved_cloud.colors)
assert np.allclose(colours_np, colours / 255, rtol=1e-5, atol=1e-8)


def transform_cloud_with_se3(cloud_file, se3_matrix, output_cloud_file):
assert str(cloud_file).endswith(".pcd") or str(cloud_file).endswith(".ply")
assert is_se3_matrix(se3_matrix)[0], is_se3_matrix(se3_matrix)[1]
assert str(output_cloud_file).endswith(".pcd") or str(output_cloud_file).endswith(".ply")
cloud = o3d.io.read_point_cloud(str(cloud_file))
cloud.transform(se3_matrix)
o3d.io.write_point_cloud(str(output_cloud_file), cloud)
logger.info(f"Transformed point cloud with SE(3) and saved as {output_cloud_file}")
23 changes: 13 additions & 10 deletions oxford_spires_utils/trajectory/file_interfaces/nerf.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def __init__(self, file_path, nerf_reader_valid_folder_path="", nerf_reader_sort
self.valid_folder_path = nerf_reader_valid_folder_path
self.sort_timestamp = nerf_reader_sort_timestamp

def read_file(self):
def read_file(self, has_timestamp=True):
"""
Read NeRF trajectory file (transforms.json)
@return: PosePath3D from evo
Expand All @@ -44,21 +44,24 @@ def read_file(self):
if self.valid_folder_path != "":
if not frame["file_path"].startswith(self.valid_folder_path):
continue
t_float128 = NeRFTrajUtils.get_t_float128_from_fname(frame["file_path"])
T = np.array(frame["transform_matrix"])
assert T.shape == (4, 4)
assert np.allclose(T[3, :], np.array([0, 0, 0, 1]))
timestamps.append(t_float128)
poses_se3.append(T)
if has_timestamp:
t_float128 = NeRFTrajUtils.get_t_float128_from_fname(frame["file_path"])
timestamps.append(t_float128)

timestamps = np.array(timestamps)
poses_se3 = np.array(poses_se3)
if self.sort_timestamp:
sort_idx = np.argsort(timestamps)
timestamps = timestamps[sort_idx]
poses_se3 = poses_se3[sort_idx]

return evo.core.trajectory.PoseTrajectory3D(poses_se3=poses_se3, timestamps=timestamps)
if has_timestamp:
timestamps = np.array(timestamps)
if self.sort_timestamp:
sort_idx = np.argsort(timestamps)
timestamps = timestamps[sort_idx]
poses_se3 = poses_se3[sort_idx]
return evo.core.trajectory.PoseTrajectory3D(poses_se3=poses_se3, timestamps=timestamps)

return evo.core.trajectory.PosePath3D(poses_se3=poses_se3)


class NeRFTrajWriter(BasicTrajWriter):
Expand Down
Loading

0 comments on commit 736f941

Please sign in to comment.