#!/usr/bin/env python3 from __future__ import annotations import argparse import json import math import os from pathlib import Path from typing import Optional, Tuple import cv2 import numpy as np from PIL import Image def quaternion_to_rotation_matrix(q: Tuple[float, float, float, float]) -> np.ndarray: w, x, y, z = q xx, yy, zz = x * x, y * y, z * z xy, xz, yz = x * y, x * z, y * z wx, wy, wz = w * x, w * y, w * z return np.array( [ [1 - 2 * (yy + zz), 2 * (xy - wz), 2 * (xz + wy)], [2 * (xy + wz), 1 - 2 * (xx + zz), 2 * (yz - wx)], [2 * (xz - wy), 2 * (yz + wx), 1 - 2 * (xx + yy)], ], dtype=np.float32, ) def calculate_vertical_fov(camera_fov: float, width: int, height: int) -> float: hfov_rad = math.radians(camera_fov) aspect_ratio = width / height vfov_rad = 2 * math.atan(math.tan(hfov_rad / 2) / aspect_ratio) return math.degrees(vfov_rad) def scaled_size(width: int, height: int, max_width: int, max_height: int) -> tuple[int, int]: scale = min(max_width / width, max_height / height, 1.0) return max(1, round(width * scale)), max(1, round(height * scale)) def resize_depth_for_upload(depth_u16: np.ndarray, size: tuple[int, int]) -> np.ndarray: # Matches the upload staging intent: depth uses linear/Triangle-like interpolation. return cv2.resize(depth_u16, size, interpolation=cv2.INTER_LINEAR) def resize_rgb_for_upload(rgb: np.ndarray, size: tuple[int, int]) -> np.ndarray: # Matches upload staging intent: RGB uses Lanczos. return np.asarray(Image.fromarray(rgb).resize(size, Image.Resampling.LANCZOS)) def depth_to_pointcloud( depth_img: np.ndarray, camera_fov: float, drone_orientation: Tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0), drone_position: np.ndarray = np.zeros(3), subsample_step: int = 1, min_depth: float = 0.1, max_depth: float = 800.0, min_height: float = -50.0, max_height: float = 1.0, ) -> Tuple[np.ndarray, np.ndarray]: rows, cols = depth_img.shape u = np.arange(0, cols, subsample_step) v = np.arange(0, rows, subsample_step) u_grid, v_grid = np.meshgrid(u, v) depths = depth_img[v_grid, u_grid] valid_mask = (depths > min_depth) & (depths <= max_depth) depths = depths[valid_mask] u_grid = u_grid[valid_mask] v_grid = v_grid[valid_mask] if depths.size == 0: return np.empty((0, 3), dtype=np.float32), np.empty((0, 2), dtype=np.int32) half_cols = cols / 2.0 half_rows = rows / 2.0 fov_x = camera_fov * math.pi / 180.0 fov_y = calculate_vertical_fov(camera_fov, cols, rows) * math.pi / 180.0 tan_fov_x = 2.0 * math.tan(fov_x / 2.0) / cols tan_fov_y = 2.0 * math.tan(fov_y / 2.0) / rows x_cam = depths y_cam = (u_grid - half_cols) * tan_fov_x * depths # Match the verified visualization convention, with vertical camera axis flipped # for the downsampled point cloud output requested here. z_cam = (v_grid - half_rows) * tan_fov_y * depths points_cam = np.column_stack((x_cam, y_cam, z_cam)).astype(np.float32) rotation_matrix = quaternion_to_rotation_matrix(tuple(drone_orientation)) drone_position = np.asarray(drone_position, dtype=np.float32).reshape(3) points_world = points_cam @ rotation_matrix.T + drone_position height_mask = (points_world[:, 2] >= min_height) & (points_world[:, 2] <= max_height) return points_world[height_mask], np.column_stack((v_grid[height_mask], u_grid[height_mask])) def write_ply_ascii(path: Path, points: np.ndarray, colors: Optional[np.ndarray]) -> None: path.parent.mkdir(parents=True, exist_ok=True) with path.open("w") as f: f.write("ply\nformat ascii 1.0\n") f.write(f"element vertex {len(points)}\n") f.write("property float x\nproperty float y\nproperty float z\n") if colors is not None: f.write("property uchar red\nproperty uchar green\nproperty uchar blue\n") f.write("end_header\n") if colors is None: for p in points: f.write(f"{p[0]:.5f} {p[1]:.5f} {p[2]:.5f}\n") else: for p, c in zip(points, colors): f.write(f"{p[0]:.5f} {p[1]:.5f} {p[2]:.5f} {int(c[0])} {int(c[1])} {int(c[2])}\n") def get_frame_ids(img_dir: Path) -> list[str]: return [p.stem for p in sorted(img_dir.glob("*.png"), key=lambda x: int(x.stem))] def parse_args() -> argparse.Namespace: parser = argparse.ArgumentParser(description="Generate point cloud from upload-downsampled MRQ depth/RGB.") parser.add_argument("--path-dir", type=Path, default=Path("/data1/MRQ/DekoClass_night/path00")) parser.add_argument("--output", type=Path, default=Path("/data1/MRQ/alignment_test_outputs/DekoClass_night_path00_downsampled_depth2pointcloud.ply")) parser.add_argument("--start", type=int, default=0) parser.add_argument("--frames", type=int, default=80) parser.add_argument("--max-width", type=int, default=1280) parser.add_argument("--max-height", type=int, default=720) parser.add_argument("--camera-fov", type=float, default=90.0) parser.add_argument("--subsample-step", type=int, default=6) parser.add_argument("--min-depth", type=float, default=0.0) parser.add_argument("--max-depth", type=float, default=100.0) parser.add_argument("--min-height", type=float, default=-200.0) parser.add_argument("--max-height-world", type=float, default=100.0) parser.add_argument("--max-points", type=int, default=1_200_000) parser.add_argument("--seed", type=int, default=19) return parser.parse_args() def main() -> int: args = parse_args() img_dir = args.path_dir / "image" depth_dir = args.path_dir / "depth" camera_dir = args.path_dir / "camera" frame_ids = get_frame_ids(img_dir)[args.start : args.start + args.frames] rng = np.random.default_rng(args.seed) merged_points: list[np.ndarray] = [] merged_colors: list[np.ndarray] = [] original_size = None downsampled_size = None for idx, frame_id in enumerate(frame_ids, start=1): depth_raw = cv2.imread(str(depth_dir / f"{frame_id}.png"), cv2.IMREAD_UNCHANGED) color_bgr = cv2.imread(str(img_dir / f"{frame_id}.png"), cv2.IMREAD_COLOR) if depth_raw is None or color_bgr is None: print(f"skip missing frame {frame_id}") continue h, w = depth_raw.shape[:2] original_size = [w, h] size = scaled_size(w, h, args.max_width, args.max_height) downsampled_size = [size[0], size[1]] depth_ds = resize_depth_for_upload(depth_raw, size).astype(np.float32) / 100.0 color_rgb = cv2.cvtColor(color_bgr, cv2.COLOR_BGR2RGB) color_ds = resize_rgb_for_upload(color_rgb, size) with open(camera_dir / f"{frame_id}.json", "r") as f: camera = json.load(f) points, pixel_coords = depth_to_pointcloud( depth_img=depth_ds, camera_fov=args.camera_fov, drone_orientation=tuple(camera["orientation"]), drone_position=np.asarray(camera["position"], dtype=np.float32), subsample_step=args.subsample_step, min_depth=args.min_depth, max_depth=args.max_depth, min_height=args.min_height, max_height=args.max_height_world, ) if points.size == 0: continue colors = color_ds[pixel_coords[:, 0], pixel_coords[:, 1]] merged_points.append(points.astype(np.float32)) merged_colors.append(colors.astype(np.uint8)) print(f"frame {idx}/{len(frame_ids)} {frame_id}: {len(points)} points") if not merged_points: raise SystemExit("no points generated") points = np.vstack(merged_points) colors = np.vstack(merged_colors) if args.max_points > 0 and len(points) > args.max_points: keep = rng.choice(len(points), size=args.max_points, replace=False) points = points[keep] colors = colors[keep] write_ply_ascii(args.output, points, colors) summary = { "path_dir": str(args.path_dir), "output": str(args.output), "frames": [frame_ids[0], frame_ids[-1]], "frame_count": len(frame_ids), "original_size": original_size, "downsampled_size": downsampled_size, "camera_fov": args.camera_fov, "subsample_step_on_downsampled_depth": args.subsample_step, "point_count": int(len(points)), "note": "RGB/depth are first downsampled to upload resolution; extrinsics are unchanged; FOV-based intrinsics are recomputed from the downsampled width/height.", } summary_path = args.output.with_suffix(".summary.json") summary_path.write_text(json.dumps(summary, indent=2) + "\n") print(json.dumps(summary, indent=2)) return 0 if __name__ == "__main__": raise SystemExit(main())