Skip to content

Commit

Permalink
drop open3d dep, replaced by pure numpy
Browse files Browse the repository at this point in the history
  • Loading branch information
MedericFourmy committed Oct 30, 2024
1 parent a86aa36 commit 4140164
Show file tree
Hide file tree
Showing 6 changed files with 24 additions and 23 deletions.
2 changes: 1 addition & 1 deletion environment.yml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
name: happypose_torch2
#name: happypose_torch2
channels:
- conda-forge
- pytorch
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ RUN source $CONDA_DIR/bin/activate && \
pip install selenium omegaconf simplejson line_profiler opencv-python \
torchnet tqdm lxml transforms3d panda3d joblib xarray pandas xarray matplotlib \
bokeh plyfile trimesh wget ipdb panda3d-gltf colorama pyyaml ipykernel \
scipy pypng h5py seaborn kornia meshcat pyarrow dt_apriltags open3d structlog \
scipy pypng h5py seaborn kornia meshcat pyarrow dt_apriltags structlog \
imageio

# Blender
Expand Down Expand Up @@ -132,7 +132,6 @@ RUN apt-get install -y tmux
# Install TEASER++
RUN apt install -y cmake libeigen3-dev libboost-all-dev \
&& source $CONDA_DIR/bin/activate \
&& pip install open3d \
&& mkdir /build && cd /build && git clone https://github.com/MIT-SPARK/TEASER-plusplus.git \
&& cd TEASER-plusplus && mkdir build && cd build \
&& cmake -DTEASERPP_PYTHON_VERSION=3.9 .. && make teaserpp_python \
Expand Down
7 changes: 0 additions & 7 deletions happypose/pose_estimators/megapose/inference/refiner_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,6 @@

# Third Party
import numpy as np
import open3d as o3d


def numpy_to_open3d(xyz):
pcd = o3d.geometry.PointCloud()
pcd.points = o3d.utility.Vector3dVector(xyz)
return pcd


def compute_masks(mask_type, depth_rendered, depth_measured, depth_delta_thresh=0.1):
Expand Down
19 changes: 7 additions & 12 deletions happypose/pose_estimators/megapose/inference/teaserpp_refiner.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,10 @@
from happypose.pose_estimators.megapose.inference.depth_refiner import DepthRefiner
from happypose.pose_estimators.megapose.inference.refiner_utils import (
compute_masks,
numpy_to_open3d,
)
from happypose.pose_estimators.megapose.inference.types import PoseEstimatesType
from happypose.toolbox.lib3d.rigid_mesh_database import BatchedMeshes
from happypose.toolbox.lib3d.transform_ops import transform_pts_np
from happypose.toolbox.renderer.panda3d_batch_renderer import Panda3dBatchRenderer
from happypose.toolbox.renderer.types import Panda3dLightData
from happypose.toolbox.visualization.meshcat_utils import get_pointcloud
Expand Down Expand Up @@ -137,16 +137,11 @@ def compute_teaserpp_refinement(

solution = solver.getSolution()

T = np.eye(4)
T[:3, :3] = solution.rotation
T[:3, 3] = solution.translation
T_tgt_src = T

# check number of inliers
pc_src_o3d = numpy_to_open3d(pc_src)
pc_src_o3d_refined = pc_src_o3d.transform(T_tgt_src)
pc_src_refined = np.array(pc_src_o3d_refined.points)
T_tgt_src = np.eye(4)
T_tgt_src[:3, :3] = solution.rotation
T_tgt_src[:3, 3] = solution.translation

pc_src_refined = transform_pts_np(T_tgt_src, pc_src)
diff = np.linalg.norm(pc_src_refined - pc_tgt, axis=-1)
inliers = np.count_nonzero(diff < solver_params.noise_bound)

Expand All @@ -158,8 +153,8 @@ def compute_teaserpp_refinement(
"pc_tgt": pc_tgt,
"pc_src_mask": pc_src_mask,
"pc_tgt_mask": pc_tgt_mask,
"T": T,
"T_tgt_src": T, # transform that aligns src to tgt
"T": T_tgt_src,
"T_tgt_src": T_tgt_src, # transform that aligns src to tgt
"num_inliers": inliers,
}

Expand Down
15 changes: 15 additions & 0 deletions happypose/toolbox/lib3d/transform_ops.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,28 @@

# Third Party
import numpy as np
import numpy.typing as npt
import torch
import transforms3d

# Local Folder
from happypose.toolbox.lib3d.rotations import compute_rotation_matrix_from_ortho6d


def transform_pts_np(T: npt.NDArray, pts: npt.NDArray):
"""Args:
----
T (torch.Tensor): (4, 4), homogeneous matrix representing a SE(3) transformation
pts (torch.Tensor): (n_pts, 3), 3D points to be transformed by T
Returns
-------
npt.NDArray: (n_pts, 3)
"""

return (T[:3, :3] @ pts.T + T[:3, 3].reshape((3, 1))).T


def transform_pts(T: torch.Tensor, pts: torch.Tensor) -> torch.Tensor:
"""Args:
----
Expand Down
1 change: 0 additions & 1 deletion pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@ ipython = "^8.29.0"
joblib = "^1.4.2"
meshcat = "^0.3.2"
omegaconf = "^2.3.0"
open3d = "^0.18.0"
opencv-contrib-python = {optional = true, version = "^4.10.0.84"}
opencv-python = {optional = true, version = "^4.10.0.84"}
panda3d = "^1.10.14"
Expand Down

0 comments on commit 4140164

Please sign in to comment.