-
Notifications
You must be signed in to change notification settings - Fork 134
/
kinfu.cu
340 lines (287 loc) · 14.5 KB
/
kinfu.cu
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
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
#include "util.hpp"
#include <png++/png.hpp>
////////////////////////////////////////////////////////////////////////////////
void get_frustum_bounds(float* K, std::vector<std::vector<float>> &extrinsic_poses, int base_frame, int curr_frame, float* camera_relative_pose, float* view_bounds,
float vox_unit, int* vox_size, float* vox_range_cam) {
// Use two extrinsic matrices to compute relative rotations between current frame and first frame
std::vector<float> ex_pose1 = extrinsic_poses[base_frame];
std::vector<float> ex_pose2 = extrinsic_poses[curr_frame];
float * ex_mat1 = &ex_pose1[0];
float * ex_mat2 = &ex_pose2[0];
float ex_mat1_inv[16] = {0};
invert_matrix(ex_mat1, ex_mat1_inv);
multiply_matrix(ex_mat1_inv, ex_mat2, camera_relative_pose);
// Init cam view frustum
float max_depth = 0.8;
float cam_view_frustum[15] =
{ 0, -320 * max_depth / K[0], -320 * max_depth / K[0], 320 * max_depth / K[0], 320 * max_depth / K[0],
0, -240 * max_depth / K[0], 240 * max_depth / K[0], 240 * max_depth / K[0], -240 * max_depth / K[0],
0, max_depth, max_depth, max_depth, max_depth
};
// Rotate cam view frustum wrt Rt
for (int i = 0; i < 5; i++) {
float tmp_arr[3] = {0};
tmp_arr[0] = camera_relative_pose[0 * 4 + 0] * cam_view_frustum[0 + i] + camera_relative_pose[0 * 4 + 1] * cam_view_frustum[5 + i] + camera_relative_pose[0 * 4 + 2] * cam_view_frustum[2 * 5 + i];
tmp_arr[1] = camera_relative_pose[1 * 4 + 0] * cam_view_frustum[0 + i] + camera_relative_pose[1 * 4 + 1] * cam_view_frustum[5 + i] + camera_relative_pose[1 * 4 + 2] * cam_view_frustum[2 * 5 + i];
tmp_arr[2] = camera_relative_pose[2 * 4 + 0] * cam_view_frustum[0 + i] + camera_relative_pose[2 * 4 + 1] * cam_view_frustum[5 + i] + camera_relative_pose[2 * 4 + 2] * cam_view_frustum[2 * 5 + i];
cam_view_frustum[0 * 5 + i] = tmp_arr[0] + camera_relative_pose[3];
cam_view_frustum[1 * 5 + i] = tmp_arr[1] + camera_relative_pose[7];
cam_view_frustum[2 * 5 + i] = tmp_arr[2] + camera_relative_pose[11];
}
// Compute frustum endpoints
float range2test[3][2] = {0};
for (int i = 0; i < 3; i++) {
range2test[i][0] = *std::min_element(&cam_view_frustum[i * 5], &cam_view_frustum[i * 5] + 5);
range2test[i][1] = *std::max_element(&cam_view_frustum[i * 5], &cam_view_frustum[i * 5] + 5);
}
// Compute frustum bounds wrt volume
for (int i = 0; i < 3; i++) {
view_bounds[i * 2 + 0] = std::max(0.0f, std::floor((range2test[i][0] - vox_range_cam[i * 2 + 0]) / vox_unit));
view_bounds[i * 2 + 1] = std::min((float)(vox_size[i]), std::ceil((range2test[i][1] - vox_range_cam[i * 2 + 0]) / vox_unit + 1));
}
}
////////////////////////////////////////////////////////////////////////////////
void save_volume_to_ply(const std::string &file_name, int* vox_size, float* vox_tsdf, float* vox_weight) {
float tsdf_threshold = 0.2f;
float weight_threshold = 1.0f;
// float radius = 5.0f;
// Count total number of points in point cloud
int num_points = 0;
for (int i = 0; i < vox_size[0] * vox_size[1] * vox_size[2]; i++)
if (std::abs(vox_tsdf[i]) < tsdf_threshold && vox_weight[i] > weight_threshold)
num_points++;
// Create header for ply file
FILE *fp = fopen(file_name.c_str(), "w");
fprintf(fp, "ply\n");
fprintf(fp, "format binary_little_endian 1.0\n");
fprintf(fp, "element vertex %d\n", num_points);
fprintf(fp, "property float x\n");
fprintf(fp, "property float y\n");
fprintf(fp, "property float z\n");
fprintf(fp, "end_header\n");
// Create point cloud content for ply file
for (int i = 0; i < vox_size[0] * vox_size[1] * vox_size[2]; i++) {
// If TSDF value of voxel is less than some threshold, add voxel coordinates to point cloud
if (std::abs(vox_tsdf[i]) < tsdf_threshold && vox_weight[i] > weight_threshold) {
// Compute voxel indices in int for higher positive number range
int z = floor(i / (vox_size[0] * vox_size[1]));
int y = floor((i - (z * vox_size[0] * vox_size[1])) / vox_size[0]);
int x = i - (z * vox_size[0] * vox_size[1]) - (y * vox_size[0]);
// Convert voxel indices to float, and save coordinates to ply file
float float_x = (float) x;
float float_y = (float) y;
float float_z = (float) z;
fwrite(&float_x, sizeof(float), 1, fp);
fwrite(&float_y, sizeof(float), 1, fp);
fwrite(&float_z, sizeof(float), 1, fp);
}
}
fclose(fp);
}
bool read_depth_data(const std::string &file_name, unsigned short * data) {
png::image< png::gray_pixel_16 > img(file_name.c_str(), png::require_color_space< png::gray_pixel_16 >());
int index = 0;
for (int i = 0; i < 480; ++i) {
for (int j = 0; j < 640; ++j) {
unsigned short s = img.get_pixel(j, i);
*(data + index) = s;
++index;
}
}
return true;
}
////////////////////////////////////////////////////////////////////////////////
__global__
void integrate(float* K, unsigned short* depth_data, float* view_bounds, float* camera_relative_pose,
float vox_unit, float vox_mu, int* vox_size, float* vox_range_cam, float* vox_tsdf, float* vox_weight) {
int z = blockIdx.x;
int y = threadIdx.x;
if (z < (int)view_bounds[2 * 2 + 0] || z >= (int)view_bounds[2 * 2 + 1])
return;
if (y < (int)view_bounds[1 * 2 + 0] || y >= (int)view_bounds[1 * 2 + 1])
return;
for (int x = view_bounds[0 * 2 + 0]; x < view_bounds[0 * 2 + 1]; x++) {
// grid to world coords
float tmp_pos[3] = {0};
tmp_pos[0] = (x + 1) * vox_unit + vox_range_cam[0 * 2 + 0];
tmp_pos[1] = (y + 1) * vox_unit + vox_range_cam[1 * 2 + 0];
tmp_pos[2] = (z + 1) * vox_unit + vox_range_cam[2 * 2 + 0];
// transform
float tmp_arr[3] = {0};
tmp_arr[0] = tmp_pos[0] - camera_relative_pose[3];
tmp_arr[1] = tmp_pos[1] - camera_relative_pose[7];
tmp_arr[2] = tmp_pos[2] - camera_relative_pose[11];
tmp_pos[0] = camera_relative_pose[0 * 4 + 0] * tmp_arr[0] + camera_relative_pose[1 * 4 + 0] * tmp_arr[1] + camera_relative_pose[2 * 4 + 0] * tmp_arr[2];
tmp_pos[1] = camera_relative_pose[0 * 4 + 1] * tmp_arr[0] + camera_relative_pose[1 * 4 + 1] * tmp_arr[1] + camera_relative_pose[2 * 4 + 1] * tmp_arr[2];
tmp_pos[2] = camera_relative_pose[0 * 4 + 2] * tmp_arr[0] + camera_relative_pose[1 * 4 + 2] * tmp_arr[1] + camera_relative_pose[2 * 4 + 2] * tmp_arr[2];
if (tmp_pos[2] <= 0)
continue;
int px = roundf(K[0] * (tmp_pos[0] / tmp_pos[2]) + K[2]);
int py = roundf(K[4] * (tmp_pos[1] / tmp_pos[2]) + K[5]);
if (px < 1 || px > 640 || py < 1 || py > 480)
continue;
float p_depth = *(depth_data + (py - 1) * 640 + (px - 1)) / 1000.f;
if (p_depth < 0.2 || p_depth > 0.8)
continue;
if (roundf(p_depth * 1000.0f) == 0)
continue;
float eta = (p_depth - tmp_pos[2]) * sqrtf(1 + powf((tmp_pos[0] / tmp_pos[2]), 2) + powf((tmp_pos[1] / tmp_pos[2]), 2));
if (eta <= -vox_mu)
continue;
// Integrate
int volumeIDX = z * vox_size[0] * vox_size[1] + y * vox_size[0] + x;
float sdf = fmin(1.0f, eta / vox_mu);
float w_old = vox_weight[volumeIDX];
float w_new = w_old + 1.0f;
vox_weight[volumeIDX] = w_new;
vox_tsdf[volumeIDX] = (vox_tsdf[volumeIDX] * w_old + sdf) / w_new;
}
}
void vol2bin() {
// Write data to binary file
// std::string volume_filename = "volume.tsdf.bin";
// std::ofstream out_file(volume_filename, std::ios::binary | std::ios::out);
// for (int i = 0; i < vox_size[0] * vox_size[1] * vox_size[2]; i++)
// out_file.write((char*)&vox_tsdf[i], sizeof(float));
// out_file.close();
}
void FatalError(const int lineNumber = 0) {
std::cerr << "FatalError";
if (lineNumber != 0) std::cerr << " at LINE " << lineNumber;
std::cerr << ". Program Terminated." << std::endl;
cudaDeviceReset();
exit(EXIT_FAILURE);
}
void checkCUDA(const int lineNumber, cudaError_t status) {
if (status != cudaSuccess) {
std::cerr << "CUDA failure at LINE " << lineNumber << ": " << status << std::endl;
FatalError();
}
}
int main(int argc, char **argv) {
std::string data_directory = "data";
std::string sequence_directory = data_directory + "/sample";
// Get file list of color images
std::vector<std::string> file_list_color;
std::string color_regex = ".color.png";
get_files_in_directory(sequence_directory, file_list_color, color_regex);
std::sort(file_list_color.begin(), file_list_color.end());
// Get file list of depth images
std::vector<std::string> file_list_depth;
std::string depth_regex = ".depth.png";
get_files_in_directory(sequence_directory, file_list_depth, depth_regex);
std::sort(file_list_depth.begin(), file_list_depth.end());
// Get file list of intrinsics
std::vector<std::string> file_list_intrinsics;
std::string intrinsics_regex = ".K.txt";
get_files_in_directory(sequence_directory, file_list_intrinsics, intrinsics_regex);
std::sort(file_list_intrinsics.begin(), file_list_intrinsics.end());
// Get file list of extrinsics
std::vector<std::string> file_list_extrinsics;
std::string extrinsics_regex = ".pose.txt";
get_files_in_directory(sequence_directory, file_list_extrinsics, extrinsics_regex);
std::sort(file_list_extrinsics.begin(), file_list_extrinsics.end());
// Load intrinsics (3x3 matrix)
std::string intrinsic_filename = sequence_directory + "/intrinsics.K.txt";
std::vector<float> K_vec = load_matrix_from_file(intrinsic_filename, 3, 3);
float K[9];
for (int i = 0; i < 9; i++)
K[i] = K_vec[i];
// Load extrinsics (4x4 matrices)
std::vector<std::vector<float>> extrinsics;
for (std::string &curr_filename : file_list_extrinsics) {
std::string curr_extrinsic_filename = sequence_directory + "/" + curr_filename;
std::vector<float> curr_extrinsic = load_matrix_from_file(curr_extrinsic_filename, 4, 4);
extrinsics.push_back(curr_extrinsic);
}
// Init voxel volume params
float vox_unit = 0.001; // in meters
float vox_mu_grid = 5;
float vox_mu = vox_unit * vox_mu_grid;
int vox_size[3];
float vox_range_cam[6];
float * vox_tsdf;
float * vox_weight;
vox_size[0] = 512;
vox_size[1] = 512;
vox_size[2] = 512;
vox_range_cam[0 * 2 + 0] = -(float)(vox_size[0]) * vox_unit / 2;
vox_range_cam[0 * 2 + 1] = vox_range_cam[0 * 2 + 0] + (float)(vox_size[0]) * vox_unit;
vox_range_cam[1 * 2 + 0] = -(float)(vox_size[1]) * vox_unit / 2;
vox_range_cam[1 * 2 + 1] = vox_range_cam[1 * 2 + 0] + (float)(vox_size[1]) * vox_unit;
vox_range_cam[2 * 2 + 0] = -50.0f * vox_unit;
vox_range_cam[2 * 2 + 1] = vox_range_cam[2 * 2 + 0] + (float)(vox_size[2]) * vox_unit;
vox_tsdf = new float[vox_size[0] * vox_size[1] * vox_size[2]];
vox_weight = new float[vox_size[0] * vox_size[1] * vox_size[2]];
memset(vox_weight, 0, sizeof(float) * vox_size[0] * vox_size[1] * vox_size[2]);
for (int i = 0; i < vox_size[0] * vox_size[1] * vox_size[2]; i++)
vox_tsdf[i] = 1.0f;
// Copy voxel volume to GPU
int * d_vox_size;
float * d_vox_tsdf;
float * d_vox_weight;
cudaMalloc(&d_vox_size, 3 * sizeof(float));
cudaMalloc(&d_vox_tsdf, vox_size[0] * vox_size[1] * vox_size[2] * sizeof(float));
cudaMalloc(&d_vox_weight, vox_size[0] * vox_size[1] * vox_size[2] * sizeof(float));
checkCUDA(__LINE__, cudaGetLastError());
cudaMemcpy(d_vox_size, vox_size, 3 * sizeof(float), cudaMemcpyHostToDevice);
cudaMemcpy(d_vox_tsdf, vox_tsdf, vox_size[0] * vox_size[1] * vox_size[2] * sizeof(float), cudaMemcpyHostToDevice);
cudaMemcpy(d_vox_weight, vox_weight, vox_size[0] * vox_size[1] * vox_size[2] * sizeof(float), cudaMemcpyHostToDevice);
checkCUDA(__LINE__, cudaGetLastError());
// Allocate GPU to hold fusion params
float * d_K;
unsigned short * d_depth_data;
float * d_view_bounds;
float * d_camera_relative_pose;
float * d_vox_range_cam;
cudaMalloc(&d_K, 9 * sizeof(float));
cudaMalloc(&d_depth_data, 480 * 640 * sizeof(unsigned short));
cudaMalloc(&d_view_bounds, 6 * sizeof(float));
cudaMalloc(&d_camera_relative_pose, 16 * sizeof(float));
cudaMalloc(&d_vox_range_cam, 6 * sizeof(float));
checkCUDA(__LINE__, cudaGetLastError());
// Set first frame of sequence as base coordinate frame
int base_frame = 0;
// Fuse frames
for (int curr_frame = 0; curr_frame < file_list_depth.size(); curr_frame++) {
std::cerr << "Fusing frame " << curr_frame << "...";
// Load image/depth/extrinsic data for current frame
unsigned short * depth_data = (unsigned short *) malloc(480 * 640 * sizeof(unsigned short));
std::string curr_filename = sequence_directory + "/" + file_list_depth[curr_frame];
read_depth_data(curr_filename, depth_data);
// Compute relative camera pose transform between current frame and base frame
// Compute camera view frustum bounds within the voxel volume
float camera_relative_pose[16] = {0};
float view_bounds[6] = {0};
get_frustum_bounds(K, extrinsics, base_frame, curr_frame, camera_relative_pose, view_bounds,
vox_unit, vox_size, vox_range_cam);
// Copy fusion params to GPU
cudaMemcpy(d_K, K, 9 * sizeof(float), cudaMemcpyHostToDevice);
cudaMemcpy(d_depth_data, depth_data, 480 * 640 * sizeof(unsigned short), cudaMemcpyHostToDevice);
cudaMemcpy(d_view_bounds, view_bounds, 6 * sizeof(float), cudaMemcpyHostToDevice);
cudaMemcpy(d_camera_relative_pose, camera_relative_pose, 16 * sizeof(float), cudaMemcpyHostToDevice);
cudaMemcpy(d_vox_range_cam, vox_range_cam, 6 * sizeof(float), cudaMemcpyHostToDevice);
checkCUDA(__LINE__, cudaGetLastError());
// Integrate
// integrateCPU(K, depth_data, view_bounds, camera_relative_pose,
// vox_unit, vox_mu, vox_range_cam, vox_tsdf, vox_weight);
int CUDA_NUM_BLOCKS = vox_size[2];
int CUDA_NUM_THREADS = vox_size[1];
integrate <<< CUDA_NUM_BLOCKS, CUDA_NUM_THREADS >>>(d_K, d_depth_data, d_view_bounds, d_camera_relative_pose,
vox_unit, vox_mu, d_vox_size, d_vox_range_cam, d_vox_tsdf, d_vox_weight);
checkCUDA(__LINE__, cudaGetLastError());
// Clear memory
free(depth_data);
std::cerr << " done!" << std::endl;
// If at the last frame, save current TSDF volume to point cloud visualization
std::string scene_ply_name = "volume.pointcloud.ply";
if (curr_frame == file_list_depth.size() - 1) {
// Copy data back to memory
cudaMemcpy(vox_tsdf, d_vox_tsdf, vox_size[0] * vox_size[1] * vox_size[2] * sizeof(float), cudaMemcpyDeviceToHost);
cudaMemcpy(vox_weight, d_vox_weight, vox_size[0] * vox_size[1] * vox_size[2] * sizeof(float), cudaMemcpyDeviceToHost);
checkCUDA(__LINE__, cudaGetLastError());
save_volume_to_ply(scene_ply_name, vox_size, vox_tsdf, vox_weight);
}
}
return 0;
}