-
Notifications
You must be signed in to change notification settings - Fork 10
/
BasicAPI.cpp
1380 lines (1140 loc) · 47 KB
/
BasicAPI.cpp
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
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include <boost/filesystem.hpp>
#include <sys/stat.h>
#include <dirent.h>
#include "BasicAPI.h"
#include "GCSLAM/ORBSLAM/ORBextractor.h"
#include "Tools/RealSenseInterface.h"
using namespace std;
using namespace cv;
using namespace MultiViewGeometry;
namespace BasicAPI
{
void loadGlobalParameters(GlobalParameters &g_para, std::string para_file)
{
cv::FileStorage fSettings;
fSettings = cv::FileStorage(para_file.c_str(), cv::FileStorage::READ);
g_para.runTestFlag = fSettings["runTestFlag"];
g_para.runRefFrame = fSettings["runRefFrame"];
g_para.runNewFrame = fSettings["runNewFrame"];
g_para.runFrameNum = fSettings["runFrameNum"];
g_para.debug_mode = fSettings["debug_mode"];
g_para.salient_score_threshold = fSettings["salient_score_threshold"];
g_para.minimum_disparity = fSettings["minimum_disparity"];
g_para.ransac_maximum_iterations = fSettings["ransac_maximum_iterations"];
g_para.reprojection_error_3d_threshold = fSettings["reprojection_error_3d_threshold"];
g_para.reprojection_error_2d_threshold = fSettings["reprojection_error_2d_threshold"];
g_para.use_fine_search = fSettings["use_fine_search"];
g_para.maximum_local_frame_match_num = fSettings["maximum_local_frame_match_num"];
g_para.remove_outlier_keyframes = fSettings["remove_outlier_keyframes"];
g_para.keyframe_minimum_distance = fSettings["keyframe_minimum_distance"];
g_para.maximum_keyframe_match_num = fSettings["maximum_keyframe_match_num"];
g_para.save_ply_files = fSettings["save_ply_files"];
g_para.max_feature_num = fSettings["max_feature_num"];
g_para.use_icp_registration = fSettings["use_icp_registration"];
g_para.icp_weight = fSettings["icp_weight"];
g_para.hamming_distance_threshold = fSettings["hamming_distance_threshold"];
g_para.far_plane_distance = fSettings["far_plane_distance"];
}
void saveTrajectoryFrameList(std::vector<Frame> &F,std::string fileName)
{
FILE * fp = fopen(fileName.c_str(), "w+");
if (fp == NULL)
{
std::cerr << "file open error ! " << fileName.c_str() << std::endl;
}
for (int i = 0; i < F.size(); i++)
{
if (F[i].tracking_success && F[i].origin_index == 0)
{
Sophus::SE3d p = F[i].pose_sophus[0];
fprintf(fp, "%.8f %.8f %.8f %.8f %.8f %.8f %.8f %.8f\n",
F[i].time_stamp,
p.translation()(0),
p.translation()(1),
p.translation()(2),
p.unit_quaternion().coeffs().data()[0],
p.unit_quaternion().coeffs().data()[1],
p.unit_quaternion().coeffs().data()[2],
p.unit_quaternion().coeffs().data()[3]);
}
}
fclose(fp);
}
void saveTrajectoryKeyFrameList(std::vector<Frame> &F,std::string fileName)
{
FILE * fp = fopen(fileName.c_str(), "w+");
if (fp == NULL)
{
std::cerr << "file open error ! " << fileName.c_str() << std::endl;
}
for (int i = 0; i < F.size(); i++)
{
if (F[i].tracking_success && F[i].origin_index == 0 && F[i].is_keyframe)
{
Sophus::SE3d p = F[i].pose_sophus[0];
fprintf(fp, "%.8f %.8f %.8f %.8f %.8f %.8f %.8f %.8f\n",
F[i].time_stamp,
p.translation()(0),
p.translation()(1),
p.translation()(2),
p.unit_quaternion().coeffs().data()[0],
p.unit_quaternion().coeffs().data()[1],
p.unit_quaternion().coeffs().data()[2],
p.unit_quaternion().coeffs().data()[3]);
}
}
fclose(fp);
}
void savePLYFiles(std::string fileName,
std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3d> > p,
std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3d> >color)
{
std::ofstream output_file(fileName.c_str(), std::ios::out | std::ios::trunc);
int pointNum = fmin(p.size(), color.size());
output_file << "ply" << std::endl;
output_file << "format ascii 1.0 { ascii/binary, format version number }" << std::endl;
output_file << "comment made by Greg Turk { comments keyword specified, like all lines }" << std::endl;
output_file << "comment this file is a cube" << std::endl;
output_file << "element vertex " << pointNum << " { define \"vertex\" element, 8 of them in file }" << std::endl;
output_file << "property float x" << std::endl;
output_file << "property float y" << std::endl;
output_file << "property float z" << std::endl;
output_file << "property uchar red" << std::endl;
output_file << "property uchar green" << std::endl;
output_file << "property uchar blue" << std::endl;
output_file << "end_header" << std::endl;
for (int i = 0; i < pointNum; i++)
{
output_file << p[i](0) << " " << p[i](1) << " " << p[i](2) << " "
<< color[i](2) << " " << color[i](1) << " " << color[i](0) << " " << std::endl;
}
output_file.close();
}
void savePLYFrame(std::string fileName, const Frame &f, const CameraPara ¶)
{
std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3d> > p;
std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3d> >color;
int width = f.depth.cols;
int height = f.depth.rows;
for (int j = 0; j < height; j++)
{
for (int i = 0; i < width; i++)
{
if (f.depth.at<unsigned short>(j, i) > 0)
{
float x, y, z;
x = (i - para.c_cx) / para.c_fx * (f.depth.at<unsigned short>(j, i)) / para.depth_scale;
y = (j - para.c_cy) / para.c_fy * (f.depth.at<unsigned short>(j, i)) / para.depth_scale;
z = f.depth.at<unsigned short>(j, i) / para.depth_scale;
Eigen::Vector3d v = applyPose(f.pose_sophus[0],Eigen::Vector3d(x,y,z));
p.push_back(Eigen::Vector3f(v(0),v(1),v(2)));
color.push_back(Eigen::Vector3i(f.rgb.at<cv::Vec3b>(j, i)[0], f.rgb.at<cv::Vec3b>(j, i)[1], f.rgb.at<cv::Vec3b>(j, i)[2]));
}
}
}
savePLYFiles(fileName,p,color);
}
int detectAndExtractFeatures(Frame &t, int feature_num, CameraPara para)
{
int frame_width = t.rgb.cols;
int frame_height = t.rgb.rows;
clock_t start, end;
start = clock();
cv::Mat feature_desc;
vector<KeyPoint> feature_points;
#if 0
Ptr<ORB> orb = ORB::create();
orb->setMaxFeatures(feature_num);
orb->detectAndCompute(t.rgb, noArray(), feature_points, feature_desc);
#else
ORB_SLAM2::ORBextractor orb(feature_num, 1.2, 8, 20, 7);
Mat grayImage;
cv::cvtColor(t.rgb, grayImage, CV_RGB2GRAY);
orb(grayImage, cv::noArray(), feature_points, feature_desc);
#endif
vector<KeyPoint> undistort_feature_points(feature_points.size());
end = clock();
double time_featureExtraction = (double)(end - start) / CLOCKS_PER_SEC * 1000;
start = clock();
#if 0
// Fill matrix with points
int N = feature_points.size();
cv::Mat mat(N, 2, CV_32F);
for (int i = 0; i<N; i++)
{
mat.at<float>(i, 0) = feature_points[i].pt.x;
mat.at<float>(i, 1) = feature_points[i].pt.y;
}
//distortion for camera 1
cv::Mat DistCoef(5, 1, CV_32F);
DistCoef.at<float>(0) = g_para.d0;
DistCoef.at<float>(1) = g_para.d1;
DistCoef.at<float>(2) = g_para.d2;
DistCoef.at<float>(3) = g_para.d3;
DistCoef.at<float>(4) = g_para.d4;
cv::Mat K = cv::Mat::eye(3, 3, CV_32F);
K.at<float>(0, 0) = para.c_fx;
K.at<float>(1, 1) = para.c_fy;
K.at<float>(0, 2) = para.c_cx;
K.at<float>(1, 2) = para.c_cy;
K.at<float>(2, 2) = 1;
// Undistort points
mat = mat.reshape(2);
cv::undistortPoints(mat, mat, K, DistCoef, cv::Mat(), K);
mat = mat.reshape(1);
// Fill undistorted keypoint vector
undistort_feature_points.resize(N);
for (int i = 0; i<N; i++)
{
cv::KeyPoint kp = feature_points[i];
kp.pt.x = mat.at<float>(i, 0);
kp.pt.y = mat.at<float>(i, 1);
undistort_feature_points[i] = kp;
}
#else
for (int i = 0; i<feature_points.size(); i++)
{
cv::KeyPoint kp = feature_points[i];
undistort_feature_points[i] = kp;
}
#endif
end = clock();
double time_undistortion = (double)(end - start) / CLOCKS_PER_SEC * 1000;
start = clock();
t.keypoints.reserve(feature_points.size());
t.local_points.reserve(feature_points.size());
#if 0
cv::Mat_<float> depth_float_tmp;
cv::Mat_<float> depth_float_tmp_out;
t.depth.convertTo(depth_float_tmp, CV_32F);
cv::bilateralFilter(depth_float_tmp, depth_float_tmp_out, 5, 5, 10); //----
depth_float_tmp_out.convertTo(t.depth, CV_16U);
#endif
for (int i = 0; i < feature_points.size(); i++)
{
feature_points[i].class_id = t.frame_index;
cv::Point2f current_pt = feature_points[i].pt;
float current_depth;
if (current_pt.x > frame_width - 1 || current_pt.y > frame_height - 1 ||
current_pt.x < 0 || current_pt.y < 0)
{
current_depth = -1;
}
else
{
current_depth = t.depth.at<unsigned short>(current_pt.y, current_pt.x) / para.depth_scale;
}
// current no 2D points are considered
if (current_depth > 0 && current_depth < para.maximum_depth)
{
t.keypoints.push_back(undistort_feature_points[i]);
cv::Point2f current_undistort_pt = undistort_feature_points[i].pt;
t.descriptor.push_back(feature_desc.row(i));
t.local_points.push_back(Eigen::Vector3d(
(current_undistort_pt.x - para.c_cx) * current_depth / para.c_fx,
(current_undistort_pt.y - para.c_cy) * current_depth / para.c_fy,
current_depth));
}
}
end = clock();
double time_selectfeatures = (double)(end - start) / CLOCKS_PER_SEC * 1000;
start = clock();
return 1;
}
void refineDepthUseNormal(float *normal, float *depth,
float fx, float fy, float cx, float cy,float width, float height)
{
int numPixels = height * width;
for(int i = 0; i < height; i++)
{
for(int j = 0; j < width; j++)
{
int pos = i * width + j;
Eigen::Vector3f viewAngle = Eigen::Vector3f((j-cx)/fx,(i-cy)/fy,1);
viewAngle.normalize();
Eigen::Vector3f normalAngle = Eigen::Vector3f(normal[pos], normal[pos + numPixels],normal[pos + numPixels * 2]);
float viewQuality = viewAngle.transpose() * normalAngle;
// normal[pos] = viewQuality;
// normal[pos + numPixels] = viewQuality;
// normal[pos + numPixels * 2] = viewQuality;
if(fabs(viewQuality) < 0.3)
{
depth[pos] = 0;
normal[pos] = 0;
normal[pos + numPixels] = 0;
normal[pos + numPixels * 2] = 0;
}
}
}
}
void findCubeCorner(Frame &frame_ref, CameraPara &cameraModel)
{
int width = frame_ref.rgb.cols;
int height = frame_ref.rgb.rows;
const float fx = cameraModel.GetFx();
const float fy = cameraModel.GetFy();
const float cx = cameraModel.GetCx();
const float cy = cameraModel.GetCy();
float * filtered_depth = (float *)frame_ref.refined_depth.data;
Eigen::MatrixXf transform = frame_ref.pose_sophus[0].matrix().block<3, 4>(0, 0).cast<float>();
Eigen::Matrix3f rotation = transform.block<3,3>(0,0);
Eigen::MatrixXf translation = transform.block<3,1>(0,3);
__m256 maxX = _mm256_set1_ps(-1e8);
__m256 maxY = _mm256_set1_ps(-1e8);
__m256 maxZ = _mm256_set1_ps(-1e8);
__m256 minX = _mm256_set1_ps(1e8);
__m256 minY = _mm256_set1_ps(1e8);
__m256 minZ = _mm256_set1_ps(1e8);
vec8 inc = vec8(0,1,2,3,4,5,6,7);
for(int i = 0; i < height; i ++)
{
for(int j = 0; j < width; j+=8)
{
int pos = i * width + j;
vec8 depth_c = _mm256_loadu_ps(&filtered_depth[pos]);
vec8 x = inc + vec8(j);
vec8 y = vec8(i);
vec8 refLocalVertexX = (x - vec8(cx)) / vec8(fx) * depth_c;
vec8 refLocalVertexY = (y - vec8(cy)) / vec8(fy) * depth_c;
vec8 refVX = vec8(rotation(0,0)) * refLocalVertexX + vec8(rotation(0,1)) * refLocalVertexY + vec8(rotation(0,2)) * depth_c + vec8(translation(0));
vec8 refVY = vec8(rotation(1,0)) * refLocalVertexX + vec8(rotation(1,1)) * refLocalVertexY + vec8(rotation(1,2)) * depth_c + vec8(translation(1));
vec8 refVZ = vec8(rotation(2,0)) * refLocalVertexX + vec8(rotation(2,1)) * refLocalVertexY + vec8(rotation(2,2)) * depth_c + vec8(translation(2));
maxX = _mm256_max_ps(refVX.xmm,maxX);
maxY = _mm256_max_ps(refVY.xmm,maxY);
maxZ = _mm256_max_ps(refVZ.xmm,maxZ);
minX = _mm256_min_ps(refVX.xmm,minX);
minY = _mm256_min_ps(refVY.xmm,minY);
minZ = _mm256_min_ps(refVZ.xmm,minZ);
}
}
Eigen::Vector3f maxCorner = Eigen::Vector3f(-1e8,-1e8,-1e8);
Eigen::Vector3f minCorner = Eigen::Vector3f(1e8,1e8,1e8);
for(int i = 0; i < 8; i++ )
{
maxCorner(0) = fmax(maxCorner(0),maxX[i]);
minCorner(0) = fmin(minCorner(0),minX[i]);
maxCorner(1) = fmax(maxCorner(1),maxY[i]);
minCorner(1) = fmin(minCorner(1),minY[i]);
maxCorner(2) = fmax(maxCorner(2),maxX[i]);
minCorner(2) = fmin(minCorner(2),minX[i]);
}
// std::cout << "find frame index: " << frame_ref.frame_index << std::endl;
// std::cout << "max Corner :" << maxCorner<< std::endl;
// std::cout << "min Corner :" << minCorner<< std::endl;
}
void refineNewframesSIMD(Frame &frame_ref, Frame &frame_new,CameraPara &cameraModel)
{
int width = frame_ref.rgb.cols;
int height = frame_ref.rgb.rows;
const float fx = cameraModel.GetFx();
const float fy = cameraModel.GetFy();
const float cx = cameraModel.GetCx();
const float cy = cameraModel.GetCy();
float * filtered_depth_new = (float *)frame_new.refined_depth.data;
float * filtered_depth = (float *)frame_ref.refined_depth.data;
assert(filtered_depth_new != NULL);
assert(filtered_depth != NULL);
float threshold = 0.05;
Eigen::MatrixXf transform_new_to_ref = (frame_ref.pose_sophus[0].inverse()*frame_new.pose_sophus[0]).matrix().block<3, 4>(0, 0).cast<float>();
Eigen::Matrix3f rotation = transform_new_to_ref.block<3,3>(0,0);
Eigen::MatrixXf translation = transform_new_to_ref.block<3,1>(0,3);
vec8 inc = vec8(0,1,2,3,4,5,6,7);
for(int i = 0; i < height; i ++)
{
for(int j = 0; j < width; j+=8)
{
int pos = i * width + j;
vec8 depth_c = _mm256_loadu_ps(&filtered_depth_new[pos]);
vec8 x = inc + vec8(j);
vec8 y = vec8(i);
vec8 refLocalVertexX = (x - vec8(cx)) / vec8(fx) * depth_c;
vec8 refLocalVertexY = (y - vec8(cy)) / vec8(fy) * depth_c;
vec8 refVX = vec8(rotation(0,0)) * refLocalVertexX + vec8(rotation(0,1)) * refLocalVertexY + vec8(rotation(0,2)) * depth_c + vec8(translation(0));
vec8 refVY = vec8(rotation(1,0)) * refLocalVertexX + vec8(rotation(1,1)) * refLocalVertexY + vec8(rotation(1,2)) * depth_c + vec8(translation(1));
vec8 refVZ = vec8(rotation(2,0)) * refLocalVertexX + vec8(rotation(2,1)) * refLocalVertexY + vec8(rotation(2,2)) * depth_c + vec8(translation(2));
vec8 ref_coord_x = refVX / refVZ * vec8(fx) + vec8(cx+0.5);
vec8 ref_coord_y = refVY / refVZ * vec8(fy) + vec8(cy+0.5);
vec8 valid1 = (ref_coord_x > vec8(1)) & (ref_coord_x < vec8(width - 1));
vec8 valid2 = (ref_coord_y > vec8(1)) & (ref_coord_y < vec8(height - 1));
valid1 = valid1 & valid2;
__m256i cameraPos = _mm256_cvtps_epi32((ref_coord_x.floor() + ref_coord_y.floor() * vec8(width)).xmm);
vec8 new_depth = _mm256_mask_i32gather_ps(_mm256_set1_ps(0.0),filtered_depth,cameraPos,(valid1.xmm),4);
valid1 = ((new_depth - refVZ) > (vec8(-threshold) * refVZ)) & ((new_depth - refVZ )< (vec8(threshold) * refVZ));
__m256 filtered_depth_c = _mm256_blendv_ps(_mm256_set1_ps(0),depth_c.xmm,valid1.xmm);
_mm256_storeu_ps(&filtered_depth_new[pos],filtered_depth_c);
}
}
}
//eliminate outliers
void refineNewframes(Frame &frame_ref, Frame &frame_new,CameraPara &cameraModel)
{
int width = frame_ref.rgb.cols;
int height = frame_ref.rgb.rows;
const float fx = cameraModel.GetFx();
const float fy = cameraModel.GetFy();
const float cx = cameraModel.GetCx();
const float cy = cameraModel.GetCy();
float * filtered_depth_new = (float *)frame_new.refined_depth.data;
float * filtered_depth = (float *)frame_ref.refined_depth.data;
assert(filtered_depth_new != NULL);
assert(filtered_depth != NULL);
float depthFar = 10.0f;
float depthNear = 0.01;
Eigen::MatrixXf transform_new_to_ref = (frame_ref.pose_sophus[0].inverse()*frame_new.pose_sophus[0]).matrix().block<3, 4>(0, 0).cast<float>();
Eigen::Matrix3f rotation = transform_new_to_ref.block<3,3>(0,0);
Eigen::MatrixXf translation = transform_new_to_ref.block<3,1>(0,3);
// depth refinement
for(int i = 0; i < height; i ++)
{
for(int j = 0; j < width; j++)
{
int pos = i * width + j;
float depth_c = filtered_depth_new[pos];
if(depth_c > depthFar || depth_c < depthNear )
{
continue;
}
Eigen::Vector3f ref_local_vertex = Eigen::Vector3f((j - cx) / fx, (i - cy) / fy, 1);
Eigen::Vector3f ref_v = rotation * ref_local_vertex * depth_c + translation;
float ref_coord_x = ref_v(0) / ref_v(2) * fx + cx;
float ref_coord_y = ref_v(1) / ref_v(2) * fy + cy;
if(ref_coord_x < 1 || ref_coord_x > width - 1 || ref_coord_y < 1 || ref_coord_y > height - 1)
{
continue;
}
int ulx = floor(ref_coord_x + 0.5);
int uly = floor(ref_coord_y + 0.5);
int ref_pos = uly * width + ulx;
float depth_ul = (filtered_depth[ref_pos]);
if(abs(depth_ul - ref_v(2)) >= 0.03 * ref_v(2) )
{
filtered_depth_new[pos] = 0;
}
}
}
return;
}
void refineKeyframesSIMD(Frame &frame_ref, Frame &frame_new,CameraPara &cameraModel)
{
int width = frame_ref.rgb.cols;
int height = frame_ref.rgb.rows;
float fx = cameraModel.GetFx();
float fy = cameraModel.GetFy();
float cx = cameraModel.GetCx();
float cy = cameraModel.GetCy();
float * filtered_depth_new = (float *)frame_new.refined_depth.data;
float * filtered_depth = (float *)frame_ref.refined_depth.data;
float * vertex_weight = (float * ) frame_ref.weight.data;
float threshold = 0.05;
assert(filtered_depth_new != NULL);
assert(filtered_depth != NULL);
float depthFar = 10.0f;
float depthNear = 0.01;
Eigen::MatrixXd transform_ref_to_new;
transform_ref_to_new = (frame_new.pose_sophus[0].inverse()*frame_ref.pose_sophus[0]).matrix().block<3, 4>(0, 0);
Eigen::Matrix3f rotation = transform_ref_to_new.cast<float>().block<3,3>(0,0);
Eigen::MatrixXf translation = transform_ref_to_new.cast<float>().block<3,1>(0,3);
Eigen::Matrix3f rotationT = rotation.transpose();
// depth refinement
int validPixels = 0;
vec8 inc = vec8(0,1,2,3,4,5,6,7);
for(int i = 0; i < height; i ++)
{
for(int j = 0; j < width; j+=8)
{
int pos = i * width + j;
vec8 depth_c = _mm256_loadu_ps(&filtered_depth[pos]);
vec8 x = inc + vec8(j);
vec8 y = vec8(i);
vec8 refLocalVertexX = (x - vec8(cx)) / vec8(fx) * depth_c;
vec8 refLocalVertexY = (y - vec8(cy)) / vec8(fy) * depth_c;
vec8 refVX = vec8(rotation(0,0)) * refLocalVertexX + vec8(rotation(0,1)) * refLocalVertexY + vec8(rotation(0,2)) * depth_c + vec8(translation(0));
vec8 refVY = vec8(rotation(1,0)) * refLocalVertexX + vec8(rotation(1,1)) * refLocalVertexY + vec8(rotation(1,2)) * depth_c + vec8(translation(1));
vec8 refVZ = vec8(rotation(2,0)) * refLocalVertexX + vec8(rotation(2,1)) * refLocalVertexY + vec8(rotation(2,2)) * depth_c + vec8(translation(2));
vec8 ref_coord_x = refVX / refVZ * vec8(fx) + vec8(cx);
vec8 ref_coord_y = refVY / refVZ * vec8(fy) + vec8(cy);
vec8 valid1 = (ref_coord_x > vec8(2)) & (ref_coord_x < vec8(width - 2));
vec8 valid2 = (ref_coord_y > vec8(2)) & (ref_coord_y < vec8(height - 2));
valid1 = valid1 & valid2;
__m256i cameraPosUL = _mm256_cvtps_epi32((ref_coord_x.floor() + ref_coord_y.floor() * vec8(width)).xmm);
__m256i cameraPosUR = _mm256_add_epi32(cameraPosUL, _mm256_set1_epi32(1));
__m256i cameraPosBL = _mm256_add_epi32(cameraPosUL, _mm256_set1_epi32(width));
__m256i cameraPosBR = _mm256_add_epi32(cameraPosUL, _mm256_set1_epi32(width + 1));
vec8 newDepthUL = _mm256_mask_i32gather_ps(_mm256_set1_ps(0.0),filtered_depth_new,cameraPosUL,(valid1.xmm),4);
vec8 newDepthUR = _mm256_mask_i32gather_ps(_mm256_set1_ps(0.0),filtered_depth_new,cameraPosUR,(valid1.xmm),4);
vec8 newDepthBL = _mm256_mask_i32gather_ps(_mm256_set1_ps(0.0),filtered_depth_new,cameraPosBL,(valid1.xmm),4);
vec8 newDepthBR = _mm256_mask_i32gather_ps(_mm256_set1_ps(0.0),filtered_depth_new,cameraPosBR,(valid1.xmm),4);
vec8 deltaX = ref_coord_x - ref_coord_x.floor();
vec8 deltaY = ref_coord_y - ref_coord_y.floor();
vec8 test = (((newDepthUL - newDepthUR) < vec8(0.1)) & ((newDepthUL - newDepthUR) > vec8(-0.1))
& ((newDepthUL - newDepthBL) < vec8(0.1)) & ((newDepthUL - newDepthBL) > vec8(-0.1))
& ((newDepthUL - newDepthBR) < vec8(0.1)) & ((newDepthUL - newDepthBR) > vec8(-0.1)) );
__m256i cameraPosNearest = _mm256_cvtps_epi32(((ref_coord_x + vec8(0.5)).floor() + (ref_coord_y+ vec8(0.5)).floor() * vec8(width)).xmm);
vec8 newDepthNearest = _mm256_mask_i32gather_ps(_mm256_set1_ps(0.0),filtered_depth,cameraPosNearest,(valid1.xmm),4);
vec8 bilinearDepth = (vec8(1) - vec8(deltaX)) * (vec8(1) - vec8(deltaY)) * newDepthUL +
(vec8(1) - vec8(deltaX)) * (vec8(deltaY)) * newDepthUR +
(vec8(deltaX)) * (vec8(1) - vec8(deltaY)) * newDepthBL +
(vec8(deltaX)) * (vec8(deltaY)) * newDepthBR;
bilinearDepth.xmm = _mm256_blendv_ps(newDepthNearest.xmm,bilinearDepth.xmm,test.xmm);
valid1 = (bilinearDepth - refVZ > vec8(-threshold) * refVZ) & (bilinearDepth - refVZ < vec8(threshold) * refVZ);
vec8 scale = bilinearDepth / refVZ;
refVX = refVX * scale - vec8(translation(0));
refVY = refVY * scale - vec8(translation(1));
refVZ = refVZ * scale - vec8(translation(2));
vec8 vZ = vec8(rotationT(2,0)) * refVX + vec8(rotationT(2,1)) * refVY + vec8(rotationT(2,2)) * refVZ;
vec8 weight = _mm256_loadu_ps(&vertex_weight[pos]);
vec8 filteredDepth = (depth_c * weight + vZ) / (weight + vec8(1));
vec8 filteredWeight = weight + vec8(1);
filteredDepth.xmm = _mm256_blendv_ps(depth_c.xmm,filteredDepth.xmm,valid1.xmm);
filteredWeight.xmm = _mm256_blendv_ps(weight.xmm,filteredWeight.xmm,valid1.xmm);
_mm256_storeu_ps(&filtered_depth[pos],filteredDepth.xmm);
_mm256_storeu_ps(&vertex_weight[pos],filteredWeight.xmm);
}
}
}
void refineKeyframes(Frame &frame_ref, Frame &frame_new,CameraPara &cameraModel)
{
int width = frame_ref.rgb.cols;
int height = frame_ref.rgb.rows;
float fx = cameraModel.GetFx();
float fy = cameraModel.GetFy();
float cx = cameraModel.GetCx();
float cy = cameraModel.GetCy();
float * filtered_depth_new = (float *)frame_new.refined_depth.data;
float * filtered_depth = (float *)frame_ref.refined_depth.data;
float * vertex_weight = (float * ) frame_ref.weight.data;
assert(filtered_depth_new != NULL);
assert(filtered_depth != NULL);
float depthFar = 10.0f;
float depthNear = 0.01;
Eigen::MatrixXd transform_ref_to_new;
transform_ref_to_new = (frame_new.pose_sophus[0].inverse()*frame_ref.pose_sophus[0]).matrix().block<3, 4>(0, 0);
Eigen::Matrix3f rotation = transform_ref_to_new.cast<float>().block<3,3>(0,0);
Eigen::MatrixXf translation = transform_ref_to_new.cast<float>().block<3,1>(0,3);
// depth refinement
int validPixels = 0;
for(int i = 0; i < height; i ++)
{
for(int j = 0; j < width; j++)
{
int pos = i * width + j;
float depth_c = filtered_depth[pos];
if(depth_c > depthFar || depth_c < depthNear )
{
continue;
}
Eigen::Vector3f new_local_vertex = Eigen::Vector3f((j - cx) / fx, (i - cy) / fy, 1);
Eigen::Vector3f new_v = rotation * new_local_vertex * depth_c + translation;
float new_coord_x = new_v(0) / new_v(2) * fx + cx;
float new_coord_y = new_v(1) / new_v(2) * fy + cy;
if(new_coord_x < 1 || new_coord_x > width - 1 || new_coord_y < 1 || new_coord_y > height - 1)
{
continue;
}
int ulx = floor(new_coord_x);
int uly = floor(new_coord_y);
int new_pos = uly * width + ulx;
float depth_ul = (filtered_depth_new[new_pos]);
float depth_ur = (filtered_depth_new[new_pos+1]);
float depth_bl = (filtered_depth_new[new_pos+width]);
float depth_br = (filtered_depth_new[new_pos+width + 1]);
float x = new_coord_x - ulx;
float y = new_coord_y - uly;
float bilinear_depth;
if(abs(depth_ul - depth_ur) < 0.1 && abs(depth_ul - depth_bl) < 0.1 && abs(depth_ul - depth_br) < 0.1 )
{
bilinear_depth = (1-x)*(1-y) * depth_ul + (1-x)*y * depth_ur + x*(1-y) * depth_bl + x*y * depth_br;
}
else
{
bilinear_depth = filtered_depth_new[(int)(floor(new_coord_y + 0.5) * width + floor(new_coord_x + 0.5))];
}
#if 1
float new_depth_observation;
Eigen::Vector3f v(0,0,0);
if(abs(bilinear_depth - new_v(2)) < 0.015 * new_v(2) )
{
new_v = new_v * ( bilinear_depth / new_v(2));
v = rotation.transpose() * ( new_v - translation );
float weight = vertex_weight[pos];
new_depth_observation = (depth_c * weight + v(2)) / (weight + 1) ;
filtered_depth[pos] = new_depth_observation;
vertex_weight[pos]++;
validPixels ++;
}
#endif
}
}
return;
}
void refineDepthUseNormalSIMD(float *normal, float *depth,
float fx, float fy, float cx, float cy,float width, float height)
{
int numPixels = height * width;
vec8 inc = vec8(0,1,2,3,4,5,6,7);
for(int i = 0; i < height; i++)
{
for(int j = 0; j < width; j += 8)
{
vec8 y = vec8(i);
vec8 x = inc + vec8(j);
int pos = i * width + j;
vec8 depth_c = _mm256_loadu_ps(&depth[pos]);
vec8 normalX = _mm256_loadu_ps(&normal[pos]);
vec8 normalY = _mm256_loadu_ps(&normal[pos + numPixels]);
vec8 normalZ = _mm256_loadu_ps(&normal[pos + numPixels * 2]);
vec8 vX = (x - vec8(cx)) / vec8(fx);
vec8 vY = (y - vec8(cy)) / vec8(fy);
vec8 vZ = vec8(1);
vec8 vRSQRT = _mm256_rsqrt_ps((vX * vX + vY * vY + vZ * vZ).xmm);
vX = vX * vRSQRT;
vY = vY * vRSQRT;
vZ = vZ * vRSQRT;
vec8 vQuality = vX * normalX + vY * normalY + vZ * normalZ;
vec8 inValid = vQuality > vec8(-0.1) & vQuality < vec8(0.1);
depth_c = _mm256_blendv_ps(depth_c.xmm,vec8(0.0).xmm,inValid.xmm);
normalX = _mm256_blendv_ps(normalX.xmm,vec8(0.0).xmm,inValid.xmm);
normalY = _mm256_blendv_ps(normalY.xmm,vec8(0.0).xmm,inValid.xmm);
normalZ = _mm256_blendv_ps(normalZ.xmm,vec8(0.0).xmm,inValid.xmm);
_mm256_storeu_ps(&normal[pos],normalX.xmm);
_mm256_storeu_ps(&normal[pos + numPixels],normalY.xmm);
_mm256_storeu_ps(&normal[pos + numPixels * 2],normalZ.xmm);
_mm256_storeu_ps(&depth[pos],depth_c.xmm);
// Eigen::Vector3f viewAngle = Eigen::Vector3f((j-cx)/fx,(i-cy)/fy,1);
// viewAngle.normalize();
// Eigen::Vector3f normalAngle = Eigen::Vector3f(normal[pos], normal[pos + numPixels],normal[pos + numPixels * 2]);
// float viewQuality = viewAngle.transpose() * normalAngle;
// if(fabs(viewQuality) < 0.3)
// {
// depth[pos] = 0;
// normal[pos] = 0;
// normal[pos + numPixels] = 0;
// normal[pos + numPixels * 2] = 0;
// }
}
}
}
// to be made into SIMD
void checkColorQuality(const cv::Mat &normalMap, cv::Mat &validColorFlag,
float fx, float fy, float cx, float cy)
{
validColorFlag.release();
int width = normalMap.cols;
int height = normalMap.rows;
validColorFlag.create(height,width,CV_8U);
float *normal = (float *)normalMap.data;
unsigned char * flag = (unsigned char *)validColorFlag.data;
int totalPixelNum = height * width;
for(int i = 0; i < height; i++)
{
for(int j = 0; j < width ; j++)
{
int pos = i * width + j;
Eigen::Vector3f viewAngle = Eigen::Vector3f((j -cx)/fx,(i-cy)/fy,1);
viewAngle.normalize();
Eigen::Vector3f normalAngle = Eigen::Vector3f(normal[pos], normal[pos + totalPixelNum],normal[pos + totalPixelNum * 2]);
float viewQuality = viewAngle.transpose() * normalAngle;
if(fabs(viewQuality) >= 0.4)
{
flag[pos] = 1;
}
}
}
}
void extractNormalMapSIMD(const cv::Mat &depthMap, cv::Mat &normalMap,
float fx, float fy, float cx, float cy)
{
int width = depthMap.cols;
int height = depthMap.rows;
normalMap.release();
normalMap.create(height,width,CV_32FC3);
float normal_threshold = 0.3;
float * depth = (float *)depthMap.data;
float * normal = (float*) normalMap.data;
int width_dst = width - 1;
int height_dst = height - 1;
vec8 inc = vec8(0,1,2,3,4,5,6,7);
for(unsigned int i = 1; i < height_dst; i++)
{
for(unsigned int j = 1; j < width_dst - 9; j+= 8)
{
vec8 depth_r = _mm256_loadu_ps(&depth[i * width + j + 1]);
vec8 depth_b = _mm256_loadu_ps(&depth[i * width + j + width]);
vec8 depth_l = _mm256_loadu_ps(&depth[i * width + j - 1]);
vec8 depth_t = _mm256_loadu_ps(&depth[i * width + j - width]);
vec8 u1 = ((inc + vec8(j) - vec8(cx)) * (depth_r - depth_l) + depth_r + depth_l) / vec8(fx);
vec8 u2 = vec8(i-cy) * (depth_r - depth_l) / vec8(fy);
vec8 u3 = depth_r - depth_l;
vec8 v1 = (inc + vec8(j) - vec8(cx)) * (depth_b - depth_t) / vec8(fx);
vec8 v2 = (vec8(i-cy) * (depth_b - depth_t) + depth_b + depth_t) / vec8(fy);
vec8 v3 = depth_b - depth_t;
vec8 nX = u2*v3 - u3*v2;
vec8 nY = u3*v1 - u1*v3;
vec8 nZ = u1*v2 - u2*v1;
vec8 nSquare = nX*nX + nY*nY + nZ*nZ;
vec8 valid = (u3 < vec8(normal_threshold)) & (u3 > vec8(-normal_threshold))
& (v3 < vec8(normal_threshold)) & (v3 > vec8(-normal_threshold))
& (nSquare > vec8(1e-24));
vec8 nRSQRT = _mm256_rsqrt_ps(nSquare.xmm);
nX = nX * nRSQRT;
nY = nY * nRSQRT;
nZ = nZ * nRSQRT;
nX = _mm256_blendv_ps(vec8(0.0).xmm,nX.xmm,valid.xmm);
nY = _mm256_blendv_ps(vec8(0.0).xmm,nY.xmm,valid.xmm);
nZ = _mm256_blendv_ps(vec8(0.0).xmm,nZ.xmm,valid.xmm);
_mm256_storeu_ps(&normal[(i*width+j)],nX.xmm);
_mm256_storeu_ps(&normal[(i*width+j) + width * height],nY.xmm);
_mm256_storeu_ps(&normal[(i*width+j) + width * height * 2],nZ.xmm);
}
}
}
void saveRefinedFrame(std::string fileName, const Frame &frame_new, const CameraPara ¶)
{
float fx,fy,cx,cy,width,height;
fx = para.c_fx;
fy = para.c_fy;
cx = para.c_cx;
cy = para.c_cy;
width = para.width;
height = para.height;
std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3d> > p;
std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3d> > color;
for (int j = 0; j < height; j++)
{
for (int i = 0; i < width; i++)
{
if (frame_new.refined_depth.at<float>(j, i) > 0)
{
float x, y, z;
x = (i - cx) / fx * (frame_new.refined_depth.at<float>(j, i)) ;
y = (j - cy) / fy * (frame_new.refined_depth.at<float>(j, i)) ;
z = frame_new.refined_depth.at<float>(j, i);
Eigen::Vector3d v = applyPose(frame_new.pose_sophus[0],Eigen::Vector3d(x,y,z));
p.push_back(Eigen::Vector3f(v(0),v(1),v(2)));
color.push_back(Eigen::Vector3i(frame_new.rgb.at<cv::Vec3b>(j, i)[0], frame_new.rgb.at<cv::Vec3b>(j, i)[1], frame_new.rgb.at<cv::Vec3b>(j, i)[2]));
}
}
}
savePLYFiles(fileName,p,color);
}
void framePreprocess(Frame &t, MultiViewGeometry::CameraPara &camera)
{
int height = t.depth.rows;
int width = t.depth.cols;
t.refined_depth.create(height,width,CV_32FC1);
t.weight.create(height,width,CV_32FC1);
for(int i = 0; i < height * width ; i++)
{
if(t.depth.at<unsigned short>(i) > camera.maximum_depth * camera.depth_scale)
{
t.depth.at<unsigned short>(i) = 0;
}
t.refined_depth.at<float>(i) = float(t.depth.at<unsigned short>(i)) / camera.depth_scale;
t.weight.at<float>(i) = 0;
}
/***************bilateral filter***************/
#if 1
cv::Mat filteredDepth;
int bilateralFilterRange = 9;
#if MobileCPU
bilateralFilterRange = 7;
#endif
cv::bilateralFilter(t.refined_depth, filteredDepth, bilateralFilterRange, 0.03,4.5);
t.refined_depth = filteredDepth;
/***************remove boundary***************/
float *refined_depth_data = (float *)t.refined_depth.data;
unsigned short *depth_data = (unsigned short*)t.depth.data;
// for(int i = 0; i < height * width; i++)
// {
// if(fabs(refined_depth_data[i] - float(depth_data[i]) / camera.depth_scale) > 0.02)
// {
// refined_depth_data[i] = 0;
// depth_data[i] = 0;
// }
// }
// removeBoundary(t.refined_depth);
#endif
for(int i = 0; i < height * width ; i++)
{
t.depth.at<unsigned short>(i) = t.refined_depth.at<float>(i) * camera.depth_scale;
}
t.depth_scale = camera.depth_scale;
// if(t.frame_index % 10 == 0)
// {
// char fileName[256];
// memset(fileName, 0, 256);
// sprintf(fileName, "output/ply/%d.ply",t.frame_index);
// MultiViewGeometry::saveRefinedFrame(fileName,t,camera);
// }
}
int LoadOnlineOPENNIData(Frame &fc,
LogReader *liveLogReader,
MultiViewGeometry::CameraPara &camera)
{
static int frame_index = 0;
assert(liveLogReader != NULL);
int width = camera.width;
int height = camera.height;
liveLogReader->getNext();
fc.frame_index = frame_index;
frame_index++;
fc.rgb.release();
fc.rgb.create(height,width,CV_8UC3);
memcpy(fc.rgb.data,liveLogReader->rgb,width*height*3);
fc.depth.release();
fc.depth.create(height,width,CV_16UC1);
memcpy(fc.depth.data,liveLogReader->depth,width*height*sizeof(short));
#if 0
char fileName[256];
memset(fileName,0,256);
sprintf(fileName,"output/img/%04d_rgb.png",fc.frame_index);
cv::imwrite(fileName,fc.rgb);
memset(fileName,0,256);
sprintf(fileName,"output/img/%04d_depth.png",fc.frame_index);
cv::imwrite(fileName,fc.depth);
#endif
framePreprocess(fc,camera);
if(fc.frame_index > 10)
{
static_cast<LiveLogReader *>(liveLogReader)->setAuto(0);
}
}
int LoadOnlineRS2Data(Frame &fc,
rs2::pipeline &pipe,
MultiViewGeometry::CameraPara &camera)
{
rs2::pipeline_profile profile = pipe.get_active_profile();
float depth_scale = get_depth_scale(profile.get_device());
rs2::frameset frameset = pipe.wait_for_frames();
auto depth_stream = profile.get_stream(RS2_STREAM_DEPTH);
auto color_stream = profile.get_stream(RS2_STREAM_COLOR);
rs2_extrinsics e = depth_stream.get_extrinsics_to(color_stream);
rs2_intrinsics depthI = depth_stream.as<rs2::video_stream_profile>().get_intrinsics();
rs2_intrinsics colorI = color_stream.as<rs2::video_stream_profile>().get_intrinsics();
Eigen::Matrix3f R;
Eigen::Vector3f t;
R << e.rotation[0],e.rotation[1],e.rotation[2],
e.rotation[3],e.rotation[4],e.rotation[5],
e.rotation[6],e.rotation[7],e.rotation[8];
t << e.translation[0], e.translation[1], e.translation[2];