-
Notifications
You must be signed in to change notification settings - Fork 11
/
pose_graph_ICP.py
175 lines (152 loc) · 7.85 KB
/
pose_graph_ICP.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
import numpy as np
import open3d as o3d
from SIFT import SIFT_Transformation
from registration import draw_registration_result
from glob import glob
import matplotlib.pyplot as plt
# Load point clouds
def load_point_clouds(voxel_size=0.0, pcds_paths=None):
pcds = []
print('len demo_icp_pcds_paths:', len(pcds_paths))
# demo_icp_pcds = o3d.data.DemoICPPointClouds()
for path in pcds_paths:
pcd = o3d.io.read_point_cloud(path)
pcd_down = pcd.voxel_down_sample(voxel_size=voxel_size)
pcds.append(pcd_down)
return pcds
def load_orginal_point_clouds(voxel_size=0.0, pcds_paths=None):
pcds = []
print('len demo_icp_pcds_paths:', len(pcds_paths))
# demo_icp_pcds = o3d.data.DemoICPPointClouds()
for path in pcds_paths:
pcd = o3d.io.read_point_cloud(path)
pcds.append(pcd)
return pcds
def pairwise_registration(source, target, init_trans):
source.estimate_normals()
target.estimate_normals()
print("Apply point-to-plane ICP")
icp_coarse = o3d.pipelines.registration.registration_icp(
source, target, max_correspondence_distance_coarse, init_trans,
o3d.pipelines.registration.TransformationEstimationPointToPlane())
icp_fine = o3d.pipelines.registration.registration_icp(
source, target, max_correspondence_distance_fine, icp_coarse.transformation,
o3d.pipelines.registration.TransformationEstimationPointToPlane())
transformation_icp = icp_fine.transformation
information_icp = o3d.pipelines.registration.get_information_matrix_from_point_clouds(
source, target, max_correspondence_distance_fine,
icp_fine.transformation)
return transformation_icp, information_icp
def full_registration(pcds, max_correspondence_distance_coarse, max_correspondence_distance_fine):
pose_graph = o3d.pipelines.registration.PoseGraph()
odometry = np.identity(4)
pose_graph.nodes.append(o3d.pipelines.registration.PoseGraphNode(odometry))
n_pcds = len(pcds) # 16
for source_id in range(n_pcds):
for target_id in range(source_id + 1, n_pcds):
print('source id:', source_id)
print('target id:', target_id)
init_trans = np.identity(4)
transformation_icp, information_icp = pairwise_registration(pcds_down[source_id], pcds_down[target_id],
init_trans)
print("Build o3d.pipelines.registration.PoseGraph")
if target_id == source_id + 1: # odometry case
odometry = np.dot((transformation_icp), odometry)
pose_graph.nodes.append(
o3d.pipelines.registration.PoseGraphNode(
np.linalg.inv(odometry)))
pose_graph.edges.append(
o3d.pipelines.registration.PoseGraphEdge(source_id,
target_id,
transformation_icp,
information_icp,
uncertain=False))
else: # loop closure case -> connect any non-neighboring nodes
pose_graph.edges.append(
o3d.pipelines.registration.PoseGraphEdge(source_id,
target_id,
transformation_icp,
information_icp,
uncertain=True))
# Loop closure
init_trans = np.identity(4)
transformation_icp, information_icp = pairwise_registration(pcds_down[n_pcds-1], pcds_down[0],
init_trans)
pose_graph.edges.append(
o3d.pipelines.registration.PoseGraphEdge(n_pcds-1,
0,
transformation_icp,
information_icp,
uncertain=False))
return pose_graph
if __name__ == "__main__":
object = "spyderman2"
if object == "castard":
depth_path = ['./train/castard/depth/align_test_depth%d.png' % i for i in range(1, 21)]
rgb_path = ['./train/castard/rgb/align_test%d.png' % i for i in range(1, 21)]
pcds_paths = ['./pcd_o3d/castard/box%d.pcd' % i for i in range(1, 19)]
elif object == "new_box":
depth_path = ['./train/new_box2/depth/align_test_depth%d.png' % i for i in range(1, 19)]
rgb_path = ['./train/new_box2/rgb/align_test%d.png' % i for i in range(1, 19)]
pcds_paths = ['./pcd_o3d/new_box2/box1%d.pcd' % i for i in range(1, 19)]
elif object == "spyderman":
depth_path = ['./train/spyderman/depth/align_test_depth%d.png' % i for i in range(1, 17)]
rgb_path = ['./train/spyderman/rgb/align_test%d.png' % i for i in range(1, 17)]
pcds_paths = ['./pcd_o3d/spyderman/spyderman%d.pcd' % i for i in range(1, 17)]
elif object == "spyderman2":
depth_path = ['./train/spyderman/depth/align_test_depth%d.png' % i for i in range(1, 23)]
rgb_path = ['./train/spyderman/rgb/align_test%d.png' % i for i in range(1, 23)]
pcds_paths = ['./pcd_o3d/spyderman2/spyderman2%d.pcd' % i for i in range(1, 23)]
# Define voxel size to Downsample
voxel_size = 0.001
origin_pcds = load_orginal_point_clouds(voxel_size, pcds_paths)
pcds_down = load_point_clouds(voxel_size, pcds_paths)
o3d.visualization.draw_geometries(pcds_down)
print("Full registration ...")
max_correspondence_distance_coarse = voxel_size * 15
max_correspondence_distance_fine = voxel_size * 1
with o3d.utility.VerbosityContextManager(o3d.utility.VerbosityLevel.Debug) as cm:
pose_graph = full_registration(pcds_down,
max_correspondence_distance_coarse,
max_correspondence_distance_fine)
print("Optimizing PoseGraph ...")
option = o3d.pipelines.registration.GlobalOptimizationOption(
max_correspondence_distance=max_correspondence_distance_fine,
edge_prune_threshold=0.25,
preference_loop_closure=2.0,
reference_node=0)
with o3d.utility.VerbosityContextManager(
o3d.utility.VerbosityLevel.Debug) as cm:
o3d.pipelines.registration.global_optimization(
pose_graph,
o3d.pipelines.registration.GlobalOptimizationLevenbergMarquardt(),
o3d.pipelines.registration.GlobalOptimizationConvergenceCriteria(),
option)
print("Transform points and display")
accumulated_pcd = o3d.geometry.PointCloud()
for point_id in range(len(pcds_down)):
print(pose_graph.nodes[point_id].pose)
accumulated_pcd += pcds_down[point_id].transform(pose_graph.nodes[point_id].pose)
o3d.visualization.draw_geometries([accumulated_pcd])
# o3d.io.write_point_cloud('accumulated_%s.pcd'%object, accumulated_pcd)
# y = np.asarray(accumulated_pcd.points)[:, 1]
# y_mean = np.mean(y)
# plt.plot(y)
# plt.show()
# # idx = np.array([i for i in range(len(z))], dtype=np.int)
# idx = np.where(y < 0.138)[0]
# idx = np.asarray(idx, dtype=np.int)
# interest_pcd = accumulated_pcd.select_by_index(list(idx))
# o3d.visualization.draw_geometries([interest_pcd])
# Render
vis = o3d.visualization.Visualizer()
vis.create_window('3DReconstructed')
for p in pcds_down:
vis.add_geometry(p)
axis = o3d.geometry.TriangleMesh.create_coordinate_frame(size=0.1, origin=[0, 0, 0])
vis.add_geometry(axis)
opt = vis.get_render_option()
opt.background_color = np.asarray([1, 1, 1])
opt.point_size = 1.5
vis.run()
vis.destroy_window()