Skip to content

Commit 47cdfb7

Browse files
Merge pull request #186 from agimus-project/remove_open3d
drop open3d dependency
2 parents a86aa36 + e6a9a6d commit 47cdfb7

File tree

7 files changed

+138
-657
lines changed

7 files changed

+138
-657
lines changed

environment.yml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
name: happypose_torch2
1+
#name: happypose_torch2
22
channels:
33
- conda-forge
44
- pytorch

happypose/pose_estimators/megapose/docker/Dockerfile.megapose

+1-2
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ RUN source $CONDA_DIR/bin/activate && \
5656
pip install selenium omegaconf simplejson line_profiler opencv-python \
5757
torchnet tqdm lxml transforms3d panda3d joblib xarray pandas xarray matplotlib \
5858
bokeh plyfile trimesh wget ipdb panda3d-gltf colorama pyyaml ipykernel \
59-
scipy pypng h5py seaborn kornia meshcat pyarrow dt_apriltags open3d structlog \
59+
scipy pypng h5py seaborn kornia meshcat pyarrow dt_apriltags structlog \
6060
imageio
6161

6262
# Blender
@@ -132,7 +132,6 @@ RUN apt-get install -y tmux
132132
# Install TEASER++
133133
RUN apt install -y cmake libeigen3-dev libboost-all-dev \
134134
&& source $CONDA_DIR/bin/activate \
135-
&& pip install open3d \
136135
&& mkdir /build && cd /build && git clone https://github.com/MIT-SPARK/TEASER-plusplus.git \
137136
&& cd TEASER-plusplus && mkdir build && cd build \
138137
&& cmake -DTEASERPP_PYTHON_VERSION=3.9 .. && make teaserpp_python \

happypose/pose_estimators/megapose/inference/refiner_utils.py

-7
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,6 @@
1515

1616
# Third Party
1717
import numpy as np
18-
import open3d as o3d
19-
20-
21-
def numpy_to_open3d(xyz):
22-
pcd = o3d.geometry.PointCloud()
23-
pcd.points = o3d.utility.Vector3dVector(xyz)
24-
return pcd
2518

2619

2720
def compute_masks(mask_type, depth_rendered, depth_measured, depth_delta_thresh=0.1):

happypose/pose_estimators/megapose/inference/teaserpp_refiner.py

+7-12
Original file line numberDiff line numberDiff line change
@@ -27,10 +27,10 @@
2727
from happypose.pose_estimators.megapose.inference.depth_refiner import DepthRefiner
2828
from happypose.pose_estimators.megapose.inference.refiner_utils import (
2929
compute_masks,
30-
numpy_to_open3d,
3130
)
3231
from happypose.pose_estimators.megapose.inference.types import PoseEstimatesType
3332
from happypose.toolbox.lib3d.rigid_mesh_database import BatchedMeshes
33+
from happypose.toolbox.lib3d.transform_ops import transform_pts_np
3434
from happypose.toolbox.renderer.panda3d_batch_renderer import Panda3dBatchRenderer
3535
from happypose.toolbox.renderer.types import Panda3dLightData
3636
from happypose.toolbox.visualization.meshcat_utils import get_pointcloud
@@ -137,16 +137,11 @@ def compute_teaserpp_refinement(
137137

138138
solution = solver.getSolution()
139139

140-
T = np.eye(4)
141-
T[:3, :3] = solution.rotation
142-
T[:3, 3] = solution.translation
143-
T_tgt_src = T
144-
145-
# check number of inliers
146-
pc_src_o3d = numpy_to_open3d(pc_src)
147-
pc_src_o3d_refined = pc_src_o3d.transform(T_tgt_src)
148-
pc_src_refined = np.array(pc_src_o3d_refined.points)
140+
T_tgt_src = np.eye(4)
141+
T_tgt_src[:3, :3] = solution.rotation
142+
T_tgt_src[:3, 3] = solution.translation
149143

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

@@ -158,8 +153,8 @@ def compute_teaserpp_refinement(
158153
"pc_tgt": pc_tgt,
159154
"pc_src_mask": pc_src_mask,
160155
"pc_tgt_mask": pc_tgt_mask,
161-
"T": T,
162-
"T_tgt_src": T, # transform that aligns src to tgt
156+
"T": T_tgt_src,
157+
"T_tgt_src": T_tgt_src, # transform that aligns src to tgt
163158
"num_inliers": inliers,
164159
}
165160

happypose/toolbox/lib3d/transform_ops.py

+15
Original file line numberDiff line numberDiff line change
@@ -18,13 +18,28 @@
1818

1919
# Third Party
2020
import numpy as np
21+
import numpy.typing as npt
2122
import torch
2223
import transforms3d
2324

2425
# Local Folder
2526
from happypose.toolbox.lib3d.rotations import compute_rotation_matrix_from_ortho6d
2627

2728

29+
def transform_pts_np(T: npt.NDArray, pts: npt.NDArray):
30+
"""Args:
31+
----
32+
T (torch.Tensor): (4, 4), homogeneous matrix representing a SE(3) transformation
33+
pts (torch.Tensor): (n_pts, 3), 3D points to be transformed by T
34+
35+
Returns
36+
-------
37+
npt.NDArray: (n_pts, 3)
38+
"""
39+
40+
return (T[:3, :3] @ pts.T + T[:3, 3].reshape((3, 1))).T
41+
42+
2843
def transform_pts(T: torch.Tensor, pts: torch.Tensor) -> torch.Tensor:
2944
"""Args:
3045
----

0 commit comments

Comments
 (0)