-
Notifications
You must be signed in to change notification settings - Fork 118
/
Copy pathlaserMapping.cpp
1223 lines (1007 loc) · 57 KB
/
laserMapping.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
// This is an advanced implementation of the algorithm described in the
// following paper:
// J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time.
// Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014.
// Modifier: Livox [email protected]
// Copyright 2013, Ji Zhang, Carnegie Mellon University
// Further contributions copyright (c) 2016, Southwest Research Institute
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
// 3. Neither the name of the copyright holder nor the names of its
// contributors may be used to endorse or promote products derived from this
// software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
#include <math.h>
#include <nav_msgs/Odometry.h>
#include <opencv/cv.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/kdtree/kdtree_flann.h>
#include<pcl/io/pcd_io.h>
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf/transform_datatypes.h>
#include <tf/transform_broadcaster.h>
typedef pcl::PointXYZI PointType;
int kfNum = 0;
float timeLaserCloudCornerLast = 0;
float timeLaserCloudSurfLast = 0;
float timeLaserCloudFullRes = 0;
bool newLaserCloudCornerLast = false;
bool newLaserCloudSurfLast = false;
bool newLaserCloudFullRes = false;
int laserCloudCenWidth = 10;
int laserCloudCenHeight = 5;
int laserCloudCenDepth = 10;
const int laserCloudWidth = 21;
const int laserCloudHeight = 11;
const int laserCloudDepth = 21;
const int laserCloudNum = laserCloudWidth * laserCloudHeight * laserCloudDepth;//4851
int laserCloudValidInd[125];
int laserCloudSurroundInd[125];
//corner feature
pcl::PointCloud<PointType>::Ptr laserCloudCornerLast(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr laserCloudCornerLast_down(new pcl::PointCloud<PointType>());
//surf feature
pcl::PointCloud<PointType>::Ptr laserCloudSurfLast(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr laserCloudSurfLast_down(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr laserCloudOri(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr coeffSel(new pcl::PointCloud<PointType>());
// pcl::PointCloud<PointType>::Ptr laserCloudSurround(new pcl::PointCloud<PointType>());
// pcl::PointCloud<PointType>::Ptr laserCloudSurround_corner(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr laserCloudSurround2(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr laserCloudSurround2_corner(new pcl::PointCloud<PointType>());
//corner feature in map
pcl::PointCloud<PointType>::Ptr laserCloudCornerFromMap(new pcl::PointCloud<PointType>());
//surf feature in map
pcl::PointCloud<PointType>::Ptr laserCloudSurfFromMap(new pcl::PointCloud<PointType>());
std::vector< Eigen::Matrix<float,7,1> > keyframe_pose;
std::vector< Eigen::Matrix4f > pose_map;
//all points
pcl::PointCloud<PointType>::Ptr laserCloudFullRes(new pcl::PointCloud<PointType>());
pcl::PointCloud<PointType>::Ptr laserCloudFullRes2(new pcl::PointCloud<PointType>());
pcl::PointCloud<pcl::PointXYZRGB>::Ptr laserCloudFullResColor(new pcl::PointCloud<pcl::PointXYZRGB>());
pcl::PointCloud<pcl::PointXYZRGB>::Ptr laserCloudFullResColor_pcd(new pcl::PointCloud<pcl::PointXYZRGB>());
pcl::PointCloud<PointType>::Ptr laserCloudCornerArray[laserCloudNum];
pcl::PointCloud<PointType>::Ptr laserCloudSurfArray[laserCloudNum];
pcl::PointCloud<PointType>::Ptr laserCloudCornerArray2[laserCloudNum];
pcl::PointCloud<PointType>::Ptr laserCloudSurfArray2[laserCloudNum];
pcl::KdTreeFLANN<PointType>::Ptr kdtreeCornerFromMap(new pcl::KdTreeFLANN<PointType>());
pcl::KdTreeFLANN<PointType>::Ptr kdtreeSurfFromMap(new pcl::KdTreeFLANN<PointType>());
//optimization states
float transformTobeMapped[6] = {0};
//optimization states after mapping
float transformAftMapped[6] = {0};
//last optimization states
float transformLastMapped[6] = {0};
double rad2deg(double radians)
{
return radians * 180.0 / M_PI;
}
double deg2rad(double degrees)
{
return degrees * M_PI / 180.0;
}
Eigen::Matrix4f trans_euler_to_matrix(const float *trans)
{
Eigen::Matrix4f T = Eigen::Matrix4f::Identity();
Eigen::Matrix3f R;
Eigen::AngleAxisf rollAngle(Eigen::AngleAxisf(trans[0],Eigen::Vector3f::UnitX()));
Eigen::AngleAxisf pitchAngle(Eigen::AngleAxisf(trans[1],Eigen::Vector3f::UnitY()));
Eigen::AngleAxisf yawAngle(Eigen::AngleAxisf(trans[2],Eigen::Vector3f::UnitZ()));
R = pitchAngle * rollAngle * yawAngle; //zxy
T.block<3,3>(0,0) = R;
T.block<3,1>(0,3) = Eigen::Vector3f(trans[3],trans[4],trans[5]);
return T;
}
void transformAssociateToMap()
{
Eigen::Matrix4f T_aft,T_last,T_predict;
Eigen::Matrix3f R_predict;
Eigen::Vector3f euler_predict,t_predict;
T_aft = trans_euler_to_matrix(transformAftMapped);
T_last = trans_euler_to_matrix(transformLastMapped);
T_predict = T_aft * T_last.inverse() * T_aft;
R_predict = T_predict.block<3,3>(0,0);
euler_predict = R_predict.eulerAngles(1,0,2);
t_predict = T_predict.block<3,1>(0,3);
transformTobeMapped[0] = euler_predict[0];
transformTobeMapped[1] = euler_predict[1];
transformTobeMapped[2] = euler_predict[2];
transformTobeMapped[3] = t_predict[0];
transformTobeMapped[4] = t_predict[1];
transformTobeMapped[5] = t_predict[2];
std::cout<<"DEBUG transformAftMapped : "<<transformAftMapped[0]<<" "<<transformAftMapped[1]<<" "<<transformAftMapped[2]<<" "
<<transformAftMapped[3]<<" "<<transformAftMapped[4]<<" "<<transformAftMapped[5]<<std::endl;
std::cout<<"DEBUG transformTobeMapped : "<<transformTobeMapped[0]<<" "<<transformTobeMapped[1]<<" "<<transformTobeMapped[2]<<" "
<<transformTobeMapped[3]<<" "<<transformTobeMapped[4]<<" "<<transformTobeMapped[5]<<std::endl;
}
void transformUpdate()
{
for (int i = 0; i < 6; i++) {
transformLastMapped[i] = transformAftMapped[i];
transformAftMapped[i] = transformTobeMapped[i];
}
}
//lidar coordinate sys to world coordinate sys
void pointAssociateToMap(PointType const * const pi, PointType * const po)
{
//rot z(transformTobeMapped[2])
float x1 = cos(transformTobeMapped[2]) * pi->x
- sin(transformTobeMapped[2]) * pi->y;
float y1 = sin(transformTobeMapped[2]) * pi->x
+ cos(transformTobeMapped[2]) * pi->y;
float z1 = pi->z;
//rot x(transformTobeMapped[0])
float x2 = x1;
float y2 = cos(transformTobeMapped[0]) * y1 - sin(transformTobeMapped[0]) * z1;
float z2 = sin(transformTobeMapped[0]) * y1 + cos(transformTobeMapped[0]) * z1;
//rot y(transformTobeMapped[1])then add trans
po->x = cos(transformTobeMapped[1]) * x2 + sin(transformTobeMapped[1]) * z2
+ transformTobeMapped[3];
po->y = y2 + transformTobeMapped[4];
po->z = -sin(transformTobeMapped[1]) * x2 + cos(transformTobeMapped[1]) * z2
+ transformTobeMapped[5];
po->intensity = pi->intensity;
}
//lidar coordinate sys to world coordinate sys USE S
void pointAssociateToMap_all(PointType const * const pi, PointType * const po)
{
// Eigen::Matrix4f T_aft,T_last,delta_T;
// Eigen::Matrix3f R_aft,R_last;
// Eigen::Quaternionf Q_aft,Q_last;
// Eigen::Vector3f t_aft,t_last;
// T_aft = trans_euler_to_matrix(transformAftMapped);
// T_last = trans_euler_to_matrix(transformLastMapped);
// R_aft = T_aft.block<3,3>(0,0);
// R_last = T_last.block<3,3>(0,0);
// Q_aft = R_aft;
// Q_last = R_last;
double s;
s = pi->intensity - int(pi->intensity);
//std::cout<<"DEBUG pointAssociateToMap_all s: "<<pi->intensity<<std::endl;
// Eigen::Quaternionf Q_s = Q_last.slerp(s,Q_aft);
// Eigen::Matrix3f R_s = Q_s.matrix();
// Eigen::Vector3f euler_s = R_s.eulerAngles(2,0,1);
float rx = (1-s)*transformLastMapped[0] + s * transformAftMapped[0];
float ry = (1-s)*transformLastMapped[1] + s * transformAftMapped[1];
float rz = (1-s)*transformLastMapped[2] + s * transformAftMapped[2];
float tx = (1-s)*transformLastMapped[3] + s * transformAftMapped[3];
float ty = (1-s)*transformLastMapped[4] + s * transformAftMapped[4];
float tz = (1-s)*transformLastMapped[5] + s * transformAftMapped[5];
//rot z(transformTobeMapped[2])
float x1 = cos(rz) * pi->x
- sin(rz) * pi->y;
float y1 = sin(rz) * pi->x
+ cos(rz) * pi->y;
float z1 = pi->z;
//rot x(transformTobeMapped[0])
float x2 = x1;
float y2 = cos(rx) * y1 - sin(rx) * z1;
float z2 = sin(rx) * y1 + cos(rx) * z1;
//rot y(transformTobeMapped[1])then add trans
po->x = cos(ry) * x2 + sin(ry) * z2 + tx;
po->y = y2 + ty;
po->z = -sin(ry) * x2 + cos(ry) * z2 + tz;
po->intensity = pi->intensity;
}
void RGBpointAssociateToMap(PointType const * const pi, pcl::PointXYZRGB * const po)
{
double s;
s = pi->intensity - int(pi->intensity);
// float rx = (1-s)*transformLastMapped[0] + s * transformAftMapped[0];
// float ry = (1-s)*transformLastMapped[1] + s * transformAftMapped[1];
// float rz = (1-s)*transformLastMapped[2] + s * transformAftMapped[2];
// float tx = (1-s)*transformLastMapped[3] + s * transformAftMapped[3];
// float ty = (1-s)*transformLastMapped[4] + s * transformAftMapped[4];
// float tz = (1-s)*transformLastMapped[5] + s * transformAftMapped[5];
float rx = transformAftMapped[0];
float ry = transformAftMapped[1];
float rz = transformAftMapped[2];
float tx = transformAftMapped[3];
float ty = transformAftMapped[4];
float tz = transformAftMapped[5];
//rot z(transformTobeMapped[2])
float x1 = cos(rz) * pi->x
- sin(rz) * pi->y;
float y1 = sin(rz) * pi->x
+ cos(rz) * pi->y;
float z1 = pi->z;
//rot x(transformTobeMapped[0])
float x2 = x1;
float y2 = cos(rx) * y1 - sin(rx) * z1;
float z2 = sin(rx) * y1 + cos(rx) * z1;
//rot y(transformTobeMapped[1])then add trans
po->x = cos(ry) * x2 + sin(ry) * z2 + tx;
po->y = y2 + ty;
po->z = -sin(ry) * x2 + cos(ry) * z2 + tz;
//po->intensity = pi->intensity;
float intensity = pi->intensity;
intensity = intensity - std::floor(intensity);
int reflection_map = intensity*10000;
//std::cout<<"DEBUG reflection_map "<<reflection_map<<std::endl;
if (reflection_map < 30)
{
int green = (reflection_map * 255 / 30);
po->r = 0;
po->g = green & 0xff;
po->b = 0xff;
}
else if (reflection_map < 90)
{
int blue = (((90 - reflection_map) * 255) / 60);
po->r = 0x0;
po->g = 0xff;
po->b = blue & 0xff;
}
else if (reflection_map < 150)
{
int red = ((reflection_map-90) * 255 / 60);
po->r = red & 0xff;
po->g = 0xff;
po->b = 0x0;
}
else
{
int green = (((255-reflection_map) * 255) / (255-150));
po->r = 0xff;
po->g = green & 0xff;
po->b = 0;
}
}
void pointAssociateTobeMapped(PointType const * const pi, PointType * const po)
{
//add trans then rot y
float x1 = cos(transformTobeMapped[1]) * (pi->x - transformTobeMapped[3])
- sin(transformTobeMapped[1]) * (pi->z - transformTobeMapped[5]);
float y1 = pi->y - transformTobeMapped[4];
float z1 = sin(transformTobeMapped[1]) * (pi->x - transformTobeMapped[3])
+ cos(transformTobeMapped[1]) * (pi->z - transformTobeMapped[5]);
//rot x
float x2 = x1;
float y2 = cos(transformTobeMapped[0]) * y1 + sin(transformTobeMapped[0]) * z1;
float z2 = -sin(transformTobeMapped[0]) * y1 + cos(transformTobeMapped[0]) * z1;
//rot z
po->x = cos(transformTobeMapped[2]) * x2
+ sin(transformTobeMapped[2]) * y2;
po->y = -sin(transformTobeMapped[2]) * x2
+ cos(transformTobeMapped[2]) * y2;
po->z = z2;
po->intensity = pi->intensity;
}
void laserCloudCornerLastHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudCornerLast2)
{
timeLaserCloudCornerLast = laserCloudCornerLast2->header.stamp.toSec();
laserCloudCornerLast->clear();
pcl::fromROSMsg(*laserCloudCornerLast2, *laserCloudCornerLast);
newLaserCloudCornerLast = true;
}
void laserCloudSurfLastHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudSurfLast2)
{
timeLaserCloudSurfLast = laserCloudSurfLast2->header.stamp.toSec();
laserCloudSurfLast->clear();
pcl::fromROSMsg(*laserCloudSurfLast2, *laserCloudSurfLast);
newLaserCloudSurfLast = true;
}
void laserCloudFullResHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudFullRes2)
{
timeLaserCloudFullRes = laserCloudFullRes2->header.stamp.toSec();
laserCloudFullRes->clear();
laserCloudFullResColor->clear();
pcl::fromROSMsg(*laserCloudFullRes2, *laserCloudFullRes);
newLaserCloudFullRes = true;
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "laserMapping");
ros::NodeHandle nh;
ros::Subscriber subLaserCloudCornerLast = nh.subscribe<sensor_msgs::PointCloud2>
("/laser_cloud_sharp", 100, laserCloudCornerLastHandler);
ros::Subscriber subLaserCloudSurfLast = nh.subscribe<sensor_msgs::PointCloud2>
("/laser_cloud_flat", 100, laserCloudSurfLastHandler);
ros::Subscriber subLaserCloudFullRes = nh.subscribe<sensor_msgs::PointCloud2>
("/livox_cloud", 100, laserCloudFullResHandler);
ros::Publisher pubLaserCloudSurround = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_surround", 100);
ros::Publisher pubLaserCloudSurround_corner = nh.advertise<sensor_msgs::PointCloud2>
("/laser_cloud_surround_corner", 100);
ros::Publisher pubLaserCloudFullRes = nh.advertise<sensor_msgs::PointCloud2>
("/velodyne_cloud_registered", 100);
ros::Publisher pubOdomAftMapped = nh.advertise<nav_msgs::Odometry> ("/aft_mapped_to_init", 1);
nav_msgs::Odometry odomAftMapped;
odomAftMapped.header.frame_id = "/camera_init";
odomAftMapped.child_frame_id = "/aft_mapped";
std::string map_file_path;
ros::param::get("~map_file_path",map_file_path);
double filter_parameter_corner;
ros::param::get("~filter_parameter_corner",filter_parameter_corner);
double filter_parameter_surf;
ros::param::get("~filter_parameter_surf",filter_parameter_surf);
std::vector<int> pointSearchInd;
std::vector<float> pointSearchSqDis;
PointType pointOri, pointSel, coeff;
cv::Mat matA0(10, 3, CV_32F, cv::Scalar::all(0));
cv::Mat matB0(10, 1, CV_32F, cv::Scalar::all(-1));
cv::Mat matX0(10, 1, CV_32F, cv::Scalar::all(0));
cv::Mat matA1(3, 3, CV_32F, cv::Scalar::all(0));
cv::Mat matD1(1, 3, CV_32F, cv::Scalar::all(0));
cv::Mat matV1(3, 3, CV_32F, cv::Scalar::all(0));
bool isDegenerate = false;
cv::Mat matP(6, 6, CV_32F, cv::Scalar::all(0));
//VoxelGrid
pcl::VoxelGrid<PointType> downSizeFilterCorner;
downSizeFilterCorner.setLeafSize(filter_parameter_corner, filter_parameter_corner, filter_parameter_corner);
pcl::VoxelGrid<PointType> downSizeFilterSurf;
downSizeFilterSurf.setLeafSize(filter_parameter_surf, filter_parameter_surf, filter_parameter_surf);
// pcl::VoxelGrid<PointType> downSizeFilterFull;
// downSizeFilterFull.setLeafSize(0.15, 0.15, 0.15);
for (int i = 0; i < laserCloudNum; i++) {
laserCloudCornerArray[i].reset(new pcl::PointCloud<PointType>());
laserCloudSurfArray[i].reset(new pcl::PointCloud<PointType>());
laserCloudCornerArray2[i].reset(new pcl::PointCloud<PointType>());
laserCloudSurfArray2[i].reset(new pcl::PointCloud<PointType>());
}
//------------------------------------------------------------------------------------------------------
ros::Rate rate(100);
bool status = ros::ok();
while (status) {
ros::spinOnce();
if (newLaserCloudCornerLast && newLaserCloudSurfLast && newLaserCloudFullRes &&
fabs(timeLaserCloudSurfLast - timeLaserCloudCornerLast) < 0.005 &&
fabs(timeLaserCloudFullRes - timeLaserCloudCornerLast) < 0.005) {
clock_t t1,t2,t3,t4;
t1 = clock();
newLaserCloudCornerLast = false;
newLaserCloudSurfLast = false;
newLaserCloudFullRes = false;
//transformAssociateToMap();
std::cout<<"DEBUG mapping start "<<std::endl;
PointType pointOnYAxis;
pointOnYAxis.x = 0.0;
pointOnYAxis.y = 10.0;
pointOnYAxis.z = 0.0;
pointAssociateToMap(&pointOnYAxis, &pointOnYAxis);
int centerCubeI = int((transformTobeMapped[3] + 25.0) / 50.0) + laserCloudCenWidth;
int centerCubeJ = int((transformTobeMapped[4] + 25.0) / 50.0) + laserCloudCenHeight;
int centerCubeK = int((transformTobeMapped[5] + 25.0) / 50.0) + laserCloudCenDepth;
if (transformTobeMapped[3] + 25.0 < 0) centerCubeI--;
if (transformTobeMapped[4] + 25.0 < 0) centerCubeJ--;
if (transformTobeMapped[5] + 25.0 < 0) centerCubeK--;
while (centerCubeI < 3) {
for (int j = 0; j < laserCloudHeight; j++) {
for (int k = 0; k < laserCloudDepth; k++) {
int i = laserCloudWidth - 1;
pcl::PointCloud<PointType>::Ptr laserCloudCubeCornerPointer =
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
pcl::PointCloud<PointType>::Ptr laserCloudCubeSurfPointer =
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
for (; i >= 1; i--) {
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCornerArray[i - 1 + laserCloudWidth*j + laserCloudWidth * laserCloudHeight * k];
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudSurfArray[i - 1 + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
}
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeCornerPointer;
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeSurfPointer;
laserCloudCubeCornerPointer->clear();
laserCloudCubeSurfPointer->clear();
}
}
centerCubeI++;
laserCloudCenWidth++;
}
while (centerCubeI >= laserCloudWidth - 3) {
for (int j = 0; j < laserCloudHeight; j++) {
for (int k = 0; k < laserCloudDepth; k++) {
int i = 0;
pcl::PointCloud<PointType>::Ptr laserCloudCubeCornerPointer =
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
pcl::PointCloud<PointType>::Ptr laserCloudCubeSurfPointer =
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
for (; i < laserCloudWidth - 1; i++) {
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCornerArray[i + 1 + laserCloudWidth*j + laserCloudWidth * laserCloudHeight * k];
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudSurfArray[i + 1 + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
}
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeCornerPointer;
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeSurfPointer;
laserCloudCubeCornerPointer->clear();
laserCloudCubeSurfPointer->clear();
}
}
centerCubeI--;
laserCloudCenWidth--;
}
while (centerCubeJ < 3) {
for (int i = 0; i < laserCloudWidth; i++) {
for (int k = 0; k < laserCloudDepth; k++) {
int j = laserCloudHeight - 1;
pcl::PointCloud<PointType>::Ptr laserCloudCubeCornerPointer =
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
pcl::PointCloud<PointType>::Ptr laserCloudCubeSurfPointer =
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
for (; j >= 1; j--) {
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCornerArray[i + laserCloudWidth*(j - 1) + laserCloudWidth * laserCloudHeight*k];
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudSurfArray[i + laserCloudWidth * (j - 1) + laserCloudWidth * laserCloudHeight*k];
}
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeCornerPointer;
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeSurfPointer;
laserCloudCubeCornerPointer->clear();
laserCloudCubeSurfPointer->clear();
}
}
centerCubeJ++;
laserCloudCenHeight++;
}
while (centerCubeJ >= laserCloudHeight - 3) {
for (int i = 0; i < laserCloudWidth; i++) {
for (int k = 0; k < laserCloudDepth; k++) {
int j = 0;
pcl::PointCloud<PointType>::Ptr laserCloudCubeCornerPointer =
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
pcl::PointCloud<PointType>::Ptr laserCloudCubeSurfPointer =
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
for (; j < laserCloudHeight - 1; j++) {
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCornerArray[i + laserCloudWidth*(j + 1) + laserCloudWidth * laserCloudHeight*k];
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudSurfArray[i + laserCloudWidth * (j + 1) + laserCloudWidth * laserCloudHeight*k];
}
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeCornerPointer;
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeSurfPointer;
laserCloudCubeCornerPointer->clear();
laserCloudCubeSurfPointer->clear();
}
}
centerCubeJ--;
laserCloudCenHeight--;
}
while (centerCubeK < 3) {
for (int i = 0; i < laserCloudWidth; i++) {
for (int j = 0; j < laserCloudHeight; j++) {
int k = laserCloudDepth - 1;
pcl::PointCloud<PointType>::Ptr laserCloudCubeCornerPointer =
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
pcl::PointCloud<PointType>::Ptr laserCloudCubeSurfPointer =
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
for (; k >= 1; k--) {
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCornerArray[i + laserCloudWidth*j + laserCloudWidth * laserCloudHeight*(k - 1)];
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight*(k - 1)];
}
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeCornerPointer;
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeSurfPointer;
laserCloudCubeCornerPointer->clear();
laserCloudCubeSurfPointer->clear();
}
}
centerCubeK++;
laserCloudCenDepth++;
}
while (centerCubeK >= laserCloudDepth - 3) {
for (int i = 0; i < laserCloudWidth; i++) {
for (int j = 0; j < laserCloudHeight; j++) {
int k = 0;
pcl::PointCloud<PointType>::Ptr laserCloudCubeCornerPointer =
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
pcl::PointCloud<PointType>::Ptr laserCloudCubeSurfPointer =
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k];
for (; k < laserCloudDepth - 1; k++) {
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCornerArray[i + laserCloudWidth*j + laserCloudWidth * laserCloudHeight*(k + 1)];
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight*(k + 1)];
}
laserCloudCornerArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeCornerPointer;
laserCloudSurfArray[i + laserCloudWidth * j + laserCloudWidth * laserCloudHeight * k] =
laserCloudCubeSurfPointer;
laserCloudCubeCornerPointer->clear();
laserCloudCubeSurfPointer->clear();
}
}
centerCubeK--;
laserCloudCenDepth--;
}
int laserCloudValidNum = 0;
int laserCloudSurroundNum = 0;
for (int i = centerCubeI - 2; i <= centerCubeI + 2; i++) {
for (int j = centerCubeJ - 2; j <= centerCubeJ + 2; j++) {
for (int k = centerCubeK - 2; k <= centerCubeK + 2; k++) {
if (i >= 0 && i < laserCloudWidth &&
j >= 0 && j < laserCloudHeight &&
k >= 0 && k < laserCloudDepth) {
float centerX = 50.0 * (i - laserCloudCenWidth);
float centerY = 50.0 * (j - laserCloudCenHeight);
float centerZ = 50.0 * (k - laserCloudCenDepth);
bool isInLaserFOV = false;
for (int ii = -1; ii <= 1; ii += 2) {
for (int jj = -1; jj <= 1; jj += 2) {
for (int kk = -1; kk <= 1; kk += 2) {
float cornerX = centerX + 25.0 * ii;
float cornerY = centerY + 25.0 * jj;
float cornerZ = centerZ + 25.0 * kk;
float squaredSide1 = (transformTobeMapped[3] - cornerX)
* (transformTobeMapped[3] - cornerX)
+ (transformTobeMapped[4] - cornerY)
* (transformTobeMapped[4] - cornerY)
+ (transformTobeMapped[5] - cornerZ)
* (transformTobeMapped[5] - cornerZ);
float squaredSide2 = (pointOnYAxis.x - cornerX) * (pointOnYAxis.x - cornerX)
+ (pointOnYAxis.y - cornerY) * (pointOnYAxis.y - cornerY)
+ (pointOnYAxis.z - cornerZ) * (pointOnYAxis.z - cornerZ);
float check1 = 100.0 + squaredSide1 - squaredSide2
- 10.0 * sqrt(3.0) * sqrt(squaredSide1);
float check2 = 100.0 + squaredSide1 - squaredSide2
+ 10.0 * sqrt(3.0) * sqrt(squaredSide1);
if (check1 < 0 && check2 > 0) {
isInLaserFOV = true;
}
}
}
}
if (isInLaserFOV) {
laserCloudValidInd[laserCloudValidNum] = i + laserCloudWidth * j
+ laserCloudWidth * laserCloudHeight * k;
laserCloudValidNum++;
}
laserCloudSurroundInd[laserCloudSurroundNum] = i + laserCloudWidth * j
+ laserCloudWidth * laserCloudHeight * k;
laserCloudSurroundNum++;
}
}
}
}
laserCloudCornerFromMap->clear();
laserCloudSurfFromMap->clear();
for (int i = 0; i < laserCloudValidNum; i++) {
*laserCloudCornerFromMap += *laserCloudCornerArray[laserCloudValidInd[i]];
*laserCloudSurfFromMap += *laserCloudSurfArray[laserCloudValidInd[i]];
}
int laserCloudCornerFromMapNum = laserCloudCornerFromMap->points.size();
int laserCloudSurfFromMapNum = laserCloudSurfFromMap->points.size();
laserCloudCornerLast_down->clear();
downSizeFilterCorner.setInputCloud(laserCloudCornerLast);
downSizeFilterCorner.filter(*laserCloudCornerLast_down);
int laserCloudCornerLast_downNum = laserCloudCornerLast_down->points.size();
laserCloudSurfLast_down->clear();
downSizeFilterSurf.setInputCloud(laserCloudSurfLast);
downSizeFilterSurf.filter(*laserCloudSurfLast_down);
int laserCloudSurfLast_downNum = laserCloudSurfLast_down->points.size();
std::cout<<"DEBUG MAPPING laserCloudCornerLast_down : "<<laserCloudCornerLast_down->points.size()<<" laserCloudSurfLast_down : "
<<laserCloudSurfLast_down->points.size()<<std::endl;
std::cout<<"DEBUG MAPPING laserCloudCornerLast : "<<laserCloudCornerLast->points.size()<<" laserCloudSurfLast : "
<<laserCloudSurfLast->points.size()<<std::endl;
std::cout<<"DEBUG MAPPING laserCloudCornerFromMapNum : "<<laserCloudCornerFromMapNum<<" laserCloudSurfFromMapNum : "
<<laserCloudSurfFromMapNum<<std::endl;
t2 = clock();
if (laserCloudCornerFromMapNum > 10 && laserCloudSurfFromMapNum > 100) {
//if (laserCloudSurfFromMapNum > 100) {
kdtreeCornerFromMap->setInputCloud(laserCloudCornerFromMap);
kdtreeSurfFromMap->setInputCloud(laserCloudSurfFromMap);
int num_temp = 0;
for (int iterCount = 0; iterCount < 20; iterCount++) {
num_temp++;
laserCloudOri->clear();
coeffSel->clear();
for (int i = 0; i < laserCloudCornerLast->points.size(); i++) {
pointOri = laserCloudCornerLast->points[i];
pointAssociateToMap(&pointOri, &pointSel);
//find the closest 5 points
kdtreeCornerFromMap->nearestKSearch(pointSel, 5, pointSearchInd, pointSearchSqDis);
if (pointSearchSqDis[4] < 1.5) {
float cx = 0;
float cy = 0;
float cz = 0;
for (int j = 0; j < 5; j++) {
cx += laserCloudCornerFromMap->points[pointSearchInd[j]].x;
cy += laserCloudCornerFromMap->points[pointSearchInd[j]].y;
cz += laserCloudCornerFromMap->points[pointSearchInd[j]].z;
}
cx /= 5;
cy /= 5;
cz /= 5;
//mean square error
float a11 = 0;
float a12 = 0;
float a13 = 0;
float a22 = 0;
float a23 = 0;
float a33 = 0;
for (int j = 0; j < 5; j++) {
float ax = laserCloudCornerFromMap->points[pointSearchInd[j]].x - cx;
float ay = laserCloudCornerFromMap->points[pointSearchInd[j]].y - cy;
float az = laserCloudCornerFromMap->points[pointSearchInd[j]].z - cz;
a11 += ax * ax;
a12 += ax * ay;
a13 += ax * az;
a22 += ay * ay;
a23 += ay * az;
a33 += az * az;
}
a11 /= 5;
a12 /= 5;
a13 /= 5;
a22 /= 5;
a23 /= 5;
a33 /= 5;
matA1.at<float>(0, 0) = a11;
matA1.at<float>(0, 1) = a12;
matA1.at<float>(0, 2) = a13;
matA1.at<float>(1, 0) = a12;
matA1.at<float>(1, 1) = a22;
matA1.at<float>(1, 2) = a23;
matA1.at<float>(2, 0) = a13;
matA1.at<float>(2, 1) = a23;
matA1.at<float>(2, 2) = a33;
cv::eigen(matA1, matD1, matV1);
if (matD1.at<float>(0, 0) > 3 * matD1.at<float>(0, 1)) {
float x0 = pointSel.x;
float y0 = pointSel.y;
float z0 = pointSel.z;
float x1 = cx + 0.1 * matV1.at<float>(0, 0);
float y1 = cy + 0.1 * matV1.at<float>(0, 1);
float z1 = cz + 0.1 * matV1.at<float>(0, 2);
float x2 = cx - 0.1 * matV1.at<float>(0, 0);
float y2 = cy - 0.1 * matV1.at<float>(0, 1);
float z2 = cz - 0.1 * matV1.at<float>(0, 2);
//OA = (x0 - x1, y0 - y1, z0 - z1),OB = (x0 - x2, y0 - y2, z0 - z2),AB = (x1 - x2, y1 - y2, z1 - z2)
//cross:
//| i j k |
//|x0-x1 y0-y1 z0-z1|
//|x0-x2 y0-y2 z0-z2|
float a012 = sqrt(((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))
* ((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))
+ ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))
* ((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))
+ ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))
* ((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1)));
float l12 = sqrt((x1 - x2)*(x1 - x2) + (y1 - y2)*(y1 - y2) + (z1 - z2)*(z1 - z2));
float la = ((y1 - y2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))
+ (z1 - z2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))) / a012 / l12;
float lb = -((x1 - x2)*((x0 - x1)*(y0 - y2) - (x0 - x2)*(y0 - y1))
- (z1 - z2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;
float lc = -((x1 - x2)*((x0 - x1)*(z0 - z2) - (x0 - x2)*(z0 - z1))
+ (y1 - y2)*((y0 - y1)*(z0 - z2) - (y0 - y2)*(z0 - z1))) / a012 / l12;
float ld2 = a012 / l12;
//if(fabs(ld2) > 1) continue;
float s = 1 - 0.9 * fabs(ld2);
coeff.x = s * la;
coeff.y = s * lb;
coeff.z = s * lc;
coeff.intensity = s * ld2;
if (s > 0.1) {
laserCloudOri->push_back(pointOri);
coeffSel->push_back(coeff);
}
}
}
}
//std::cout <<"DEBUG mapping select corner points : " << coeffSel->size() << std::endl;
for (int i = 0; i < laserCloudSurfLast_down->points.size(); i++) {
pointOri = laserCloudSurfLast_down->points[i];
pointAssociateToMap(&pointOri, &pointSel);
kdtreeSurfFromMap->nearestKSearch(pointSel, 8, pointSearchInd, pointSearchSqDis);
if (pointSearchSqDis[7] < 5.0) {
for (int j = 0; j < 8; j++) {
matA0.at<float>(j, 0) = laserCloudSurfFromMap->points[pointSearchInd[j]].x;
matA0.at<float>(j, 1) = laserCloudSurfFromMap->points[pointSearchInd[j]].y;
matA0.at<float>(j, 2) = laserCloudSurfFromMap->points[pointSearchInd[j]].z;
}
//matA0*matX0=matB0
//AX+BY+CZ+D = 0 <=> AX+BY+CZ=-D <=> (A/D)X+(B/D)Y+(C/D)Z = -1
//(X,Y,Z)<=>mat_a0
//A/D, B/D, C/D <=> mat_x0
cv::solve(matA0, matB0, matX0, cv::DECOMP_QR); //TODO
float pa = matX0.at<float>(0, 0);
float pb = matX0.at<float>(1, 0);
float pc = matX0.at<float>(2, 0);
float pd = 1;
//ps is the norm of the plane normal vector
//pd is the distance from point to plane
float ps = sqrt(pa * pa + pb * pb + pc * pc);
pa /= ps;
pb /= ps;
pc /= ps;
pd /= ps;
bool planeValid = true;
for (int j = 0; j < 8; j++) {
if (fabs(pa * laserCloudSurfFromMap->points[pointSearchInd[j]].x +
pb * laserCloudSurfFromMap->points[pointSearchInd[j]].y +
pc * laserCloudSurfFromMap->points[pointSearchInd[j]].z + pd) > 0.2) {
planeValid = false;
break;
}
}
if (planeValid) {
//loss fuction
float pd2 = pa * pointSel.x + pb * pointSel.y + pc * pointSel.z + pd;
//if(fabs(pd2) > 0.1) continue;
float s = 1 - 0.9 * fabs(pd2) / sqrt(sqrt(pointSel.x * pointSel.x + pointSel.y * pointSel.y + pointSel.z * pointSel.z));
coeff.x = s * pa;
coeff.y = s * pb;
coeff.z = s * pc;
coeff.intensity = s * pd2;
if (s > 0.1) {
laserCloudOri->push_back(pointOri);
coeffSel->push_back(coeff);
}
}
}
}
//std::cout <<"DEBUG mapping select all points : " << coeffSel->size() << std::endl;
float srx = sin(transformTobeMapped[0]);
float crx = cos(transformTobeMapped[0]);
float sry = sin(transformTobeMapped[1]);
float cry = cos(transformTobeMapped[1]);
float srz = sin(transformTobeMapped[2]);
float crz = cos(transformTobeMapped[2]);
int laserCloudSelNum = laserCloudOri->points.size();
if (laserCloudSelNum < 50) {
continue;
}
//|c1c3+s1s2s3 c3s1s2-c1s3 c2s1|
//| c2s3 c2c3 -s2|
//|c1s2s3-c3s1 c1c3s2+s1s3 c1c2|
//AT*A*x = AT*b
cv::Mat matA(laserCloudSelNum, 6, CV_32F, cv::Scalar::all(0));
cv::Mat matAt(6, laserCloudSelNum, CV_32F, cv::Scalar::all(0));
cv::Mat matAtA(6, 6, CV_32F, cv::Scalar::all(0));
cv::Mat matB(laserCloudSelNum, 1, CV_32F, cv::Scalar::all(0));
cv::Mat matAtB(6, 1, CV_32F, cv::Scalar::all(0));
cv::Mat matX(6, 1, CV_32F, cv::Scalar::all(0));
float debug_distance = 0;
for (int i = 0; i < laserCloudSelNum; i++) {
pointOri = laserCloudOri->points[i];
coeff = coeffSel->points[i];
float arx = (crx*sry*srz*pointOri.x + crx*crz*sry*pointOri.y - srx*sry*pointOri.z) * coeff.x
+ (-srx*srz*pointOri.x - crz*srx*pointOri.y - crx*pointOri.z) * coeff.y
+ (crx*cry*srz*pointOri.x + crx*cry*crz*pointOri.y - cry*srx*pointOri.z) * coeff.z;
float ary = ((cry*srx*srz - crz*sry)*pointOri.x
+ (sry*srz + cry*crz*srx)*pointOri.y + crx*cry*pointOri.z) * coeff.x
+ ((-cry*crz - srx*sry*srz)*pointOri.x
+ (cry*srz - crz*srx*sry)*pointOri.y - crx*sry*pointOri.z) * coeff.z;
float arz = ((crz*srx*sry - cry*srz)*pointOri.x + (-cry*crz-srx*sry*srz)*pointOri.y)*coeff.x
+ (crx*crz*pointOri.x - crx*srz*pointOri.y) * coeff.y
+ ((sry*srz + cry*crz*srx)*pointOri.x + (crz*sry-cry*srx*srz)*pointOri.y)*coeff.z;
matA.at<float>(i, 0) = arx;
matA.at<float>(i, 1) = ary;
matA.at<float>(i, 2) = arz;
//TODO: the partial derivative
matA.at<float>(i, 3) = coeff.x;
matA.at<float>(i, 4) = coeff.y;
matA.at<float>(i, 5) = coeff.z;
matB.at<float>(i, 0) = -coeff.intensity;
debug_distance += fabs(coeff.intensity);
}
cv::transpose(matA, matAt);
matAtA = matAt * matA;
matAtB = matAt * matB;
cv::solve(matAtA, matAtB, matX, cv::DECOMP_QR);
//Deterioration judgment
if (iterCount == 0) {
cv::Mat matE(1, 6, CV_32F, cv::Scalar::all(0));
cv::Mat matV(6, 6, CV_32F, cv::Scalar::all(0));
cv::Mat matV2(6, 6, CV_32F, cv::Scalar::all(0));
cv::eigen(matAtA, matE, matV);
matV.copyTo(matV2);
isDegenerate = false;
float eignThre[6] = {1, 1, 1, 1, 1, 1};
for (int i = 5; i >= 0; i--) {
if (matE.at<float>(0, i) < eignThre[i]) {
for (int j = 0; j < 6; j++) {
matV2.at<float>(i, j) = 0;
}