-
Notifications
You must be signed in to change notification settings - Fork 438
/
laser_mapping.hpp
1750 lines (1478 loc) · 83.7 KB
/
laser_mapping.hpp
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 the Lidar Odometry And Mapping (LOAM) for solid-state lidar (for example: livox lidar),
// which suffer form motion blur due the continously scan pattern and low range of fov.
// Developer: Jiarong Lin ziv.lin.ljr@gmail.com
// J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time.
// Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014.
// 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.
#ifndef LASER_MAPPING_HPP
#define LASER_MAPPING_HPP
#include <ceres/ceres.h>
#include <eigen3/Eigen/Dense>
#include <future>
#include <geometry_msgs/PoseStamped.h>
#include <iostream>
#include <math.h>
#include <mutex>
#include <nav_msgs/Odometry.h>
#include <nav_msgs/Path.h>
#include <pcl/filters/statistical_outlier_removal.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <queue>
#include <ros/ros.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <string>
#include <tf/transform_broadcaster.h>
#include <tf/transform_datatypes.h>
#include <thread>
#include <vector>
#include "cell_map_keyframe.hpp"
#include "ceres_icp.hpp"
#include "ceres_pose_graph_3d.hpp"
#include "point_cloud_registration.hpp"
#include "scene_alignment.hpp"
#include "tools/common.h"
#include "tools/pcl_tools.hpp"
#include "tools/tools_logger.hpp"
#include "tools/tools_timer.hpp"
#define PUB_SURROUND_PTS 1
#define PCD_SAVE_RAW 1
#define PUB_DEBUG_INFO 0
#define IF_PUBLISH_SURFACE_AND_CORNER_PTS 0
int g_if_undistore = 0;
int if_motion_deblur = 0;
double history_add_t_step = 0.00;
double history_add_angle_step = 0.00;
using namespace PCL_TOOLS;
using namespace Common_tools;
struct Data_pair
{
sensor_msgs::PointCloud2ConstPtr m_pc_corner;
sensor_msgs::PointCloud2ConstPtr m_pc_full;
sensor_msgs::PointCloud2ConstPtr m_pc_plane;
bool m_has_pc_corner = 0;
bool m_has_pc_full = 0;
bool m_has_pc_plane = 0;
void add_pc_corner( sensor_msgs::PointCloud2ConstPtr ros_pc )
{
m_pc_corner = ros_pc;
m_has_pc_corner = true;
}
void add_pc_plane( sensor_msgs::PointCloud2ConstPtr ros_pc )
{
m_pc_plane = ros_pc;
m_has_pc_plane = true;
}
void add_pc_full( sensor_msgs::PointCloud2ConstPtr ros_pc )
{
m_pc_full = ros_pc;
m_has_pc_full = true;
}
bool is_completed()
{
return ( m_has_pc_corner & m_has_pc_full & m_has_pc_plane );
}
};
class Point_cloud_registration;
class Laser_mapping
{
public:
int m_current_frame_index = 0;
int m_para_min_match_blur = 0.0;
int m_para_max_match_blur = 0.3;
int m_max_buffer_size = 50000000;
int m_mapping_init_accumulate_frames = 100;
int m_kmean_filter_count = 3;
int m_kmean_filter_threshold = 2.0;
double m_time_pc_corner_past = 0;
double m_time_pc_surface_past = 0;
double m_time_pc_full = 0;
double m_time_odom = 0;
double m_last_time_stamp = 0;
double m_minimum_pt_time_stamp = 0;
double m_maximum_pt_time_stamp = 1.0;
float m_last_max_blur = 0.0;
int m_odom_mode;
int m_matching_mode = 0;
int m_if_input_downsample_mode = 1;
int m_maximum_parallel_thread;
int m_maximum_mapping_buff_thread = 1; // Maximum number of thead for matching buffer update
int m_maximum_history_size = 100;
int m_para_threshold_cell_revisit = 0;
float m_para_max_angular_rate = 200.0 / 50.0; // max angular rate = 90.0 /50.0 deg/s
float m_para_max_speed = 100.0 / 50.0; // max speed = 10 m/s
float m_max_final_cost = 100.0;
int m_para_icp_max_iterations = 20;
int m_para_cere_max_iterations = 100;
int m_para_optimization_maximum_residual_block = 1e5;
double m_minimum_icp_R_diff = 0.01;
double m_minimum_icp_T_diff = 0.01;
string m_pcd_save_dir_name, m_log_save_dir_name, m_loop_save_dir_name;
std::list<pcl::PointCloud<PointType>> m_laser_cloud_corner_history;
std::list<pcl::PointCloud<PointType>> m_laser_cloud_surface_history;
std::list<pcl::PointCloud<PointType>> m_laser_cloud_full_history;
std::list<double> m_his_reg_error;
Eigen::Quaterniond m_last_his_add_q;
Eigen::Vector3d m_last_his_add_t;
//
std::map<int, float> m_map_life_time_corner;
std::map<int, float> m_map_life_time_surface;
// ouput: all visualble cube points
pcl::PointCloud<PointType>::Ptr m_laser_cloud_surround;
// surround points in map to build tree
int m_if_mapping_updated_corner = true;
int m_if_mapping_updated_surface = true;
pcl::PointCloud<PointType>::Ptr m_laser_cloud_corner_from_map;
pcl::PointCloud<PointType>::Ptr m_laser_cloud_surf_from_map;
pcl::PointCloud<PointType>::Ptr m_laser_cloud_corner_from_map_last;
pcl::PointCloud<PointType>::Ptr m_laser_cloud_surf_from_map_last;
//input & output: points in one frame. local --> global
pcl::PointCloud<PointType>::Ptr m_laser_cloud_full_res;
// input: from odom
pcl::PointCloud<PointType>::Ptr m_laser_cloud_corner_last;
pcl::PointCloud<PointType>::Ptr m_laser_cloud_surf_last;
//kd-tree
pcl::KdTreeFLANN<PointType> m_kdtree_corner_from_map;
pcl::KdTreeFLANN<PointType> m_kdtree_surf_from_map;
pcl::KdTreeFLANN<PointType> m_kdtree_corner_from_map_last;
pcl::KdTreeFLANN<PointType> m_kdtree_surf_from_map_last;
int m_laser_cloud_valid_Idx[ 1024 ];
int m_laser_cloud_surround_Idx[ 1024 ];
const Eigen::Quaterniond m_q_I = Eigen::Quaterniond( 1, 0, 0, 0 );
double m_para_buffer_RT[ 7 ] = { 0, 0, 0, 1, 0, 0, 0 };
double m_para_buffer_RT_last[ 7 ] = { 0, 0, 0, 1, 0, 0, 0 };
Eigen::Map<Eigen::Quaterniond> m_q_w_curr = Eigen::Map<Eigen::Quaterniond>( m_para_buffer_RT );
Eigen::Map<Eigen::Vector3d> m_t_w_curr = Eigen::Map<Eigen::Vector3d>( m_para_buffer_RT + 4 );
Eigen::Map<Eigen::Quaterniond> m_q_w_last = Eigen::Map<Eigen::Quaterniond>( m_para_buffer_RT_last );
Eigen::Map<Eigen::Vector3d> m_t_w_last = Eigen::Map<Eigen::Vector3d>( m_para_buffer_RT_last + 4 );
std::map<double, Data_pair *> m_map_data_pair;
std::queue<Data_pair *> m_queue_avail_data;
std::queue<nav_msgs::Odometry::ConstPtr> m_odom_que;
std::mutex m_mutex_buf;
float m_line_resolution = 0;
float m_plane_resolution = 0;
pcl::VoxelGrid<PointType> m_down_sample_filter_corner;
pcl::VoxelGrid<PointType> m_down_sample_filter_surface;
pcl::StatisticalOutlierRemoval<PointType> m_filter_k_means;
std::vector<int> m_point_search_Idx;
std::vector<float> m_point_search_sq_dis;
nav_msgs::Path m_laser_after_mapped_path, m_laser_after_loopclosure_path;
int m_if_save_to_pcd_files = 1;
PCL_point_cloud_to_pcd m_pcl_tools_aftmap;
PCL_point_cloud_to_pcd m_pcl_tools_raw;
Common_tools::File_logger m_logger_common;
Common_tools::File_logger m_logger_loop_closure;
Common_tools::File_logger m_logger_pcd;
Common_tools::File_logger m_logger_timer;
Common_tools::File_logger m_logger_matching_buff;
Scene_alignment<float> m_sceene_align;
Common_tools::Timer m_timer;
ros::Publisher m_pub_laser_cloud_surround, m_pub_laser_cloud_map, m_pub_laser_cloud_full_res, m_pub_odom_aft_mapped, m_pub_odom_aft_mapped_hight_frec;
ros::Publisher m_pub_laser_aft_mapped_path, m_pub_laser_aft_loopclosure_path;
ros::NodeHandle m_ros_node_handle;
ros::Subscriber m_sub_laser_cloud_corner_last, m_sub_laser_cloud_surf_last, m_sub_laser_odom, m_sub_laser_cloud_full_res;
ceres::Solver::Summary m_final_opt_summary;
//std::list<std::thread* > m_thread_pool;
std::list<std::future<int> *> m_thread_pool;
std::list<std::future<void> *> m_thread_match_buff_refresh;
double m_maximum_in_fov_angle;
double m_maximum_pointcloud_delay_time;
double m_maximum_search_range_corner;
double m_maximum_search_range_surface;
double m_surround_pointcloud_resolution;
double m_lastest_pc_reg_time = -3e8;
double m_lastest_pc_matching_refresh_time = -3e8;
double m_lastest_pc_income_time = -3e8;
std::mutex m_mutex_mapping;
std::mutex m_mutex_querypointcloud;
std::mutex m_mutex_buff_for_matching_corner;
std::mutex m_mutex_buff_for_matching_surface;
std::mutex m_mutex_thread_pool;
std::mutex m_mutex_ros_pub;
std::mutex m_mutex_dump_full_history;
std::mutex m_mutex_keyframe;
float m_pt_cell_resolution = 1.0;
Points_cloud_map<float> m_pt_cell_map_full;
Points_cloud_map<float> m_pt_cell_map_corners;
Points_cloud_map<float> m_pt_cell_map_planes;
int m_down_sample_replace = 1;
ros::Publisher m_pub_last_corner_pts, m_pub_last_surface_pts;
ros::Publisher m_pub_match_corner_pts, m_pub_match_surface_pts, m_pub_debug_pts, m_pub_pc_aft_loop;
std::future<void> *m_mapping_refresh_service_corner, *m_mapping_refresh_service_surface, *m_mapping_refresh_service; // Thread for mapping update
std::future<void> *m_service_pub_surround_pts, *m_service_loop_detection; // Thread for loop detection and publish surrounding pts
Common_tools::Timer timer_all;
std::mutex timer_log_mutex;
int m_if_maps_incre_update_mean_and_cov;
int m_loop_closure_if_enable;
int m_loop_closure_if_dump_keyframe_data;
int m_loop_closure_minimum_keyframe_differen;
int m_para_scans_of_each_keyframe = 0;
int m_para_scans_between_two_keyframe = 0;
int m_para_scene_alignments_maximum_residual_block;
int m_loop_closure_map_alignment_maximum_icp_iteration;
int m_loop_closure_map_alignment_if_dump_matching_result;
int m_loop_closure_maximum_keyframe_in_wating_list;
float m_loop_closure_minimum_similarity_linear;
float m_loop_closure_minimum_similarity_planar;
float m_loop_closure_map_alignment_resolution;
float m_loop_closure_map_alignment_inlier_threshold;
// ANCHOR keyframe define
//std::shared_ptr<Maps_keyframe<float>> m_current_keyframe;
std::list<std::shared_ptr<Maps_keyframe<float>>> m_keyframe_of_updating_list;
std::list<std::shared_ptr<Maps_keyframe<float>>> m_keyframe_need_precession_list;
Scene_alignment<float> m_scene_align;
ADD_SCREEN_PRINTF_OUT_METHOD;
int if_pt_in_fov( const Eigen::Matrix<double, 3, 1> &pt )
{
auto pt_affine = m_q_w_curr.inverse() * ( pt - m_t_w_curr );
if ( pt_affine( 0 ) < 0 )
return 0;
float angle = Eigen_math::vector_angle( pt_affine, Eigen::Matrix<double, 3, 1>( 1, 0, 0 ), 1 );
if ( angle * 57.3 < m_maximum_in_fov_angle )
return 1;
else
return 0;
}
void service_update_buff_for_matching_surface()
{
pcl::VoxelGrid<PointType> down_sample_filter_surface = m_down_sample_filter_surface;
while ( 1 )
{
if ( m_if_mapping_updated_surface == false )
{
std::this_thread::sleep_for( std::chrono::nanoseconds( 100 ) );
continue;
}
else
{
pcl::PointCloud<PointType>::Ptr laser_cloud_surf_from_map( new pcl::PointCloud<PointType>() );
if ( m_matching_mode )
{
pcl::VoxelGrid<PointType> down_sample_filter_surface = m_down_sample_filter_surface;
std::vector<Points_cloud_map<float>::Mapping_cell_ptr> plane_cell_vec = m_pt_cell_map_planes.find_cells_in_radius( m_t_w_curr, m_maximum_search_range_surface );
int surface_cell_numbers_full = plane_cell_vec.size();
int surface_cell_numbers_in_fov = 0;
pcl::PointCloud<PointType> pc_temp;
for ( size_t i = 0; i < plane_cell_vec.size(); i++ )
{
//*laser_cloud_surf_from_map += PCL_TOOLS::eigen_pt_to_pcl_pointcloud<PointType>( plane_cell_vec[i]->m_points_vec );
int if_in_fov = if_pt_in_fov( plane_cell_vec[ i ]->m_center.cast<double>() );
if ( if_in_fov == 0 )
{
continue;
}
surface_cell_numbers_in_fov++;
down_sample_filter_surface.setInputCloud( plane_cell_vec[ i ]->m_pcl_pc_vec.makeShared() );
down_sample_filter_surface.filter( pc_temp );
if ( m_down_sample_replace )
{
plane_cell_vec[ i ]->set_pointcloud( pc_temp );
}
*laser_cloud_surf_from_map += pc_temp;
}
screen_printf( "==== Ratio of surface in fovs %.2f ====\r\n",
( float ) surface_cell_numbers_in_fov / surface_cell_numbers_full );
}
else
{
for ( auto it = m_laser_cloud_surface_history.begin(); it != m_laser_cloud_surface_history.end(); it++ )
{
*laser_cloud_surf_from_map += ( *it );
}
}
down_sample_filter_surface.setInputCloud( laser_cloud_surf_from_map );
down_sample_filter_surface.filter( *laser_cloud_surf_from_map );
if ( laser_cloud_surf_from_map->points.size() )
{
m_kdtree_surf_from_map.setInputCloud( laser_cloud_surf_from_map );
}
m_if_mapping_updated_surface = false;
m_mutex_buff_for_matching_surface.lock();
*m_laser_cloud_surf_from_map_last = *laser_cloud_surf_from_map;
m_kdtree_surf_from_map_last = m_kdtree_surf_from_map;
m_mutex_buff_for_matching_surface.unlock();
}
}
}
void service_update_buff_for_matching_corner()
{
pcl::VoxelGrid<PointType> down_sample_filter_corner = m_down_sample_filter_corner;
while ( 1 )
{
if ( m_if_mapping_updated_corner == false )
{
std::this_thread::sleep_for( std::chrono::nanoseconds( 100 ) );
continue;
}
else
{
pcl::PointCloud<PointType>::Ptr laser_cloud_corner_from_map( new pcl::PointCloud<PointType>() );
if ( m_matching_mode )
{
pcl::VoxelGrid<PointType> down_sample_filter_corner = m_down_sample_filter_corner;
std::vector<Points_cloud_map<float>::Mapping_cell_ptr> corner_cell_vec = m_pt_cell_map_corners.find_cells_in_radius( m_t_w_curr, m_maximum_search_range_corner );
int corner_cell_numbers_full = corner_cell_vec.size();
int corner_cell_numbers_in_fov = 0;
pcl::PointCloud<PointType> pc_temp;
for ( size_t i = 0; i < corner_cell_vec.size(); i++ )
{
//*laser_cloud_corner_from_map += PCL_TOOLS::eigen_pt_to_pcl_pointcloud<PointType>( corner_cell_vec[i]->m_points_vec );
int if_in_fov = if_pt_in_fov( corner_cell_vec[ i ]->m_center.cast<double>() );
if ( if_in_fov == 0 )
{
continue;
}
corner_cell_numbers_in_fov++;
down_sample_filter_corner.setInputCloud( corner_cell_vec[ i ]->m_pcl_pc_vec.makeShared() );
down_sample_filter_corner.filter( pc_temp );
if ( m_down_sample_replace )
{
corner_cell_vec[ i ]->set_pointcloud( pc_temp );
}
*laser_cloud_corner_from_map += pc_temp;
}
screen_printf( "==== Ratio of corner in fovs %.2f ====\r\n", ( float ) corner_cell_numbers_in_fov / corner_cell_numbers_full );
}
else
{
for ( auto it = m_laser_cloud_corner_history.begin(); it != m_laser_cloud_corner_history.end(); it++ )
{
*laser_cloud_corner_from_map += ( *it );
}
}
down_sample_filter_corner.setInputCloud( laser_cloud_corner_from_map );
down_sample_filter_corner.filter( *laser_cloud_corner_from_map );
if ( laser_cloud_corner_from_map->points.size() )
{
m_kdtree_corner_from_map.setInputCloud( laser_cloud_corner_from_map );
}
m_if_mapping_updated_corner = false;
m_mutex_buff_for_matching_corner.lock();
*m_laser_cloud_corner_from_map_last = *laser_cloud_corner_from_map;
m_kdtree_corner_from_map_last = m_kdtree_corner_from_map;
m_mutex_buff_for_matching_corner.unlock();
}
}
}
void update_buff_for_matching()
{
if ( m_lastest_pc_matching_refresh_time == m_lastest_pc_reg_time )
return;
m_timer.tic( "Update buff for matching" );
pcl::VoxelGrid<PointType> down_sample_filter_corner = m_down_sample_filter_corner;
pcl::VoxelGrid<PointType> down_sample_filter_surface = m_down_sample_filter_surface;
down_sample_filter_corner.setLeafSize( m_line_resolution, m_line_resolution, m_line_resolution );
down_sample_filter_surface.setLeafSize( m_plane_resolution, m_plane_resolution, m_plane_resolution );
pcl::PointCloud<PointType>::Ptr laser_cloud_corner_from_map( new pcl::PointCloud<PointType>() );
pcl::PointCloud<PointType>::Ptr laser_cloud_surf_from_map( new pcl::PointCloud<PointType>() );
if ( m_matching_mode )
{
pcl::VoxelGrid<PointType> down_sample_filter_corner = m_down_sample_filter_corner;
pcl::VoxelGrid<PointType> down_sample_filter_surface = m_down_sample_filter_surface;
std::vector<Points_cloud_map<float>::Mapping_cell_ptr> corner_cell_vec = m_pt_cell_map_corners.find_cells_in_radius( m_t_w_curr, m_maximum_search_range_corner );
std::vector<Points_cloud_map<float>::Mapping_cell_ptr> plane_cell_vec = m_pt_cell_map_planes.find_cells_in_radius( m_t_w_curr, m_maximum_search_range_surface );
int corner_cell_numbers_in_fov = 0;
int surface_cell_numbers_in_fov = 0;
pcl::PointCloud<PointType> pc_temp;
for ( size_t i = 0; i < corner_cell_vec.size(); i++ )
{
int if_in_fov = if_pt_in_fov( corner_cell_vec[ i ]->m_center.cast<double>() );
if ( if_in_fov == 0 )
{
continue;
}
corner_cell_numbers_in_fov++;
down_sample_filter_corner.setInputCloud( corner_cell_vec[ i ]->get_pointcloud().makeShared() );
down_sample_filter_corner.filter( pc_temp );
if ( m_down_sample_replace )
{
corner_cell_vec[ i ]->set_pointcloud( pc_temp );
}
*laser_cloud_corner_from_map += pc_temp;
}
for ( size_t i = 0; i < plane_cell_vec.size(); i++ )
{
int if_in_fov = if_pt_in_fov( plane_cell_vec[ i ]->m_center.cast<double>() );
if ( if_in_fov == 0 )
{
continue;
}
surface_cell_numbers_in_fov++;
down_sample_filter_surface.setInputCloud( plane_cell_vec[ i ]->get_pointcloud().makeShared() );
down_sample_filter_surface.filter( pc_temp );
if ( m_down_sample_replace )
{
plane_cell_vec[ i ]->set_pointcloud( pc_temp );
}
*laser_cloud_surf_from_map += pc_temp;
}
}
else
{
m_mutex_mapping.lock();
for ( auto it = m_laser_cloud_corner_history.begin(); it != m_laser_cloud_corner_history.end(); it++ )
{
*laser_cloud_corner_from_map += ( *it );
}
for ( auto it = m_laser_cloud_surface_history.begin(); it != m_laser_cloud_surface_history.end(); it++ )
{
*laser_cloud_surf_from_map += ( *it );
}
m_mutex_mapping.unlock();
}
down_sample_filter_corner.setInputCloud( laser_cloud_corner_from_map );
down_sample_filter_corner.filter( *laser_cloud_corner_from_map );
down_sample_filter_surface.setInputCloud( laser_cloud_surf_from_map );
down_sample_filter_surface.filter( *laser_cloud_surf_from_map );
pcl::KdTreeFLANN<PointType> kdtree_corner_from_map;
pcl::KdTreeFLANN<PointType> kdtree_surf_from_map;
if ( laser_cloud_corner_from_map->points.size() && laser_cloud_surf_from_map->points.size() )
{
kdtree_corner_from_map.setInputCloud( laser_cloud_corner_from_map );
kdtree_surf_from_map.setInputCloud( laser_cloud_surf_from_map );
}
m_if_mapping_updated_corner = false;
m_if_mapping_updated_surface = false;
m_mutex_buff_for_matching_corner.lock();
*m_laser_cloud_corner_from_map_last = *laser_cloud_corner_from_map;
m_kdtree_corner_from_map_last = kdtree_corner_from_map;
m_mutex_buff_for_matching_surface.unlock();
m_mutex_buff_for_matching_surface.lock();
*m_laser_cloud_surf_from_map_last = *laser_cloud_surf_from_map;
m_kdtree_surf_from_map_last = kdtree_surf_from_map;
m_mutex_buff_for_matching_corner.unlock();
if ( ( m_lastest_pc_reg_time > m_lastest_pc_matching_refresh_time ) || ( m_lastest_pc_reg_time < 10 ) )
{
m_lastest_pc_matching_refresh_time = m_lastest_pc_reg_time;
}
*m_logger_matching_buff.get_ostream() << m_timer.toc_string( "Update buff for matching" ) << std::endl;
}
void service_update_buff_for_matching()
{
while ( 1 )
{
//if ( m_if_mapping_updated_corner == false and m_if_mapping_updated_surface == false )
std::this_thread::sleep_for( std::chrono::nanoseconds( 100 ) );
update_buff_for_matching();
}
}
Laser_mapping()
{
m_laser_cloud_corner_last = pcl::PointCloud<PointType>::Ptr( new pcl::PointCloud<PointType>() );
m_laser_cloud_surf_last = pcl::PointCloud<PointType>::Ptr( new pcl::PointCloud<PointType>() );
m_laser_cloud_surround = pcl::PointCloud<PointType>::Ptr( new pcl::PointCloud<PointType>() );
m_laser_cloud_corner_from_map = pcl::PointCloud<PointType>::Ptr( new pcl::PointCloud<PointType>() );
m_laser_cloud_surf_from_map = pcl::PointCloud<PointType>::Ptr( new pcl::PointCloud<PointType>() );
m_laser_cloud_corner_from_map_last = pcl::PointCloud<PointType>::Ptr( new pcl::PointCloud<PointType>() );
m_laser_cloud_surf_from_map_last = pcl::PointCloud<PointType>::Ptr( new pcl::PointCloud<PointType>() );
m_laser_cloud_full_res = pcl::PointCloud<PointType>::Ptr( new pcl::PointCloud<PointType>() );
init_parameters( m_ros_node_handle );
//livox_corners
m_sub_laser_cloud_corner_last = m_ros_node_handle.subscribe<sensor_msgs::PointCloud2>( "/pc2_corners", 10000, &Laser_mapping::laserCloudCornerLastHandler, this );
m_sub_laser_cloud_surf_last = m_ros_node_handle.subscribe<sensor_msgs::PointCloud2>( "/pc2_surface", 10000, &Laser_mapping::laserCloudSurfLastHandler, this );
m_sub_laser_cloud_full_res = m_ros_node_handle.subscribe<sensor_msgs::PointCloud2>( "/pc2_full", 10000, &Laser_mapping::laserCloudFullResHandler, this );
m_pub_laser_cloud_surround = m_ros_node_handle.advertise<sensor_msgs::PointCloud2>( "/laser_cloud_surround", 10000 );
m_pub_last_corner_pts = m_ros_node_handle.advertise<sensor_msgs::PointCloud2>( "/features_corners", 10000 );
m_pub_last_surface_pts = m_ros_node_handle.advertise<sensor_msgs::PointCloud2>( "/features_surface", 10000 );
m_pub_match_corner_pts = m_ros_node_handle.advertise<sensor_msgs::PointCloud2>( "/match_pc_corners", 10000 );
m_pub_match_surface_pts = m_ros_node_handle.advertise<sensor_msgs::PointCloud2>( "/match_pc_surface", 10000 );
m_pub_pc_aft_loop = m_ros_node_handle.advertise<sensor_msgs::PointCloud2>( "/pc_aft_loop_closure", 10000 );
m_pub_debug_pts = m_ros_node_handle.advertise<sensor_msgs::PointCloud2>( "/pc_debug", 10000 );
m_pub_laser_cloud_map = m_ros_node_handle.advertise<sensor_msgs::PointCloud2>( "/laser_cloud_map", 10000 );
m_pub_laser_cloud_full_res = m_ros_node_handle.advertise<sensor_msgs::PointCloud2>( "/velodyne_cloud_registered", 10000 );
m_pub_odom_aft_mapped = m_ros_node_handle.advertise<nav_msgs::Odometry>( "/aft_mapped_to_init", 10000 );
m_pub_odom_aft_mapped_hight_frec = m_ros_node_handle.advertise<nav_msgs::Odometry>( "/aft_mapped_to_init_high_frec", 10000 );
m_pub_laser_aft_mapped_path = m_ros_node_handle.advertise<nav_msgs::Path>( "/aft_mapped_path", 10000 );
m_pub_laser_aft_loopclosure_path = m_ros_node_handle.advertise<nav_msgs::Path>( "/aft_loopclosure_path", 10000 );
m_pt_cell_map_full.set_resolution( m_pt_cell_resolution );
m_pt_cell_map_full.m_minimum_revisit_threshold = m_para_threshold_cell_revisit;
m_pt_cell_map_corners.set_resolution( m_pt_cell_resolution );
m_pt_cell_map_corners.m_minimum_revisit_threshold = m_para_threshold_cell_revisit;
m_pt_cell_map_planes.set_resolution( m_pt_cell_resolution );
m_pt_cell_map_planes.m_minimum_revisit_threshold = m_para_threshold_cell_revisit;
m_keyframe_of_updating_list.push_back( std::make_shared<Maps_keyframe<float>>() );
//m_current_keyframe = std::make_shared<Maps_keyframe<float>>();
screen_out << "Laser_mapping init OK" << endl;
};
~Laser_mapping(){};
Data_pair *get_data_pair( const double &time_stamp )
{
std::map<double, Data_pair *>::iterator it = m_map_data_pair.find( time_stamp );
if ( it == m_map_data_pair.end() )
{
Data_pair *date_pair_ptr = new Data_pair();
m_map_data_pair.insert( std::make_pair( time_stamp, date_pair_ptr ) );
return date_pair_ptr;
}
else
{
return it->second;
}
}
template <typename T>
T get_ros_parameter( ros::NodeHandle &nh, const std::string parameter_name, T ¶meter, T default_val )
{
nh.param<T>( parameter_name.c_str(), parameter, default_val );
ENABLE_SCREEN_PRINTF;
screen_out << "[Laser_mapping_ros_param]: " << parameter_name << " ==> " << parameter << std::endl;
return parameter;
}
// ANCHOR ros_parameter_setting
void init_parameters( ros::NodeHandle &nh )
{
get_ros_parameter<float>( nh, "feature_extraction/mapping_line_resolution", m_line_resolution, 0.4 );
get_ros_parameter<float>( nh, "feature_extraction/mapping_plane_resolution", m_plane_resolution, 0.8 );
if ( m_odom_mode == 1 )
{
//m_max_buffer_size = 3e8;
}
get_ros_parameter<int>( nh, "common/if_verbose_screen_printf", m_if_verbose_screen_printf, 1 );
get_ros_parameter<int>( nh, "common/odom_mode", m_odom_mode, 0 );
get_ros_parameter<int>( nh, "common/maximum_parallel_thread", m_maximum_parallel_thread, 2 );
get_ros_parameter<int>( nh, "common/if_motion_deblur", if_motion_deblur, 0 );
get_ros_parameter<int>( nh, "common/if_save_to_pcd_files", m_if_save_to_pcd_files, 0 );
get_ros_parameter<int>( nh, "common/if_update_mean_and_cov_incrementally", m_if_maps_incre_update_mean_and_cov, 0 );
get_ros_parameter<int>( nh, "common/threshold_cell_revisit", m_para_threshold_cell_revisit, 5000 );
get_ros_parameter<double>( nh, "optimization/minimum_icp_R_diff", m_minimum_icp_R_diff, 0.01 );
get_ros_parameter<double>( nh, "optimization/minimum_icp_T_diff", m_minimum_icp_T_diff, 0.01 );
get_ros_parameter<int>( nh, "optimization/icp_maximum_iteration", m_para_icp_max_iterations, 20 );
get_ros_parameter<int>( nh, "optimization/ceres_maximum_iteration", m_para_cere_max_iterations, 20 );
get_ros_parameter<int>( nh, "optimization/maximum_residual_blocks", m_para_optimization_maximum_residual_block, 1e5 );
get_ros_parameter<float>( nh, "optimization/max_allow_incre_R", m_para_max_angular_rate, 200.0 / 50.0 );
get_ros_parameter<float>( nh, "optimization/max_allow_incre_T", m_para_max_speed, 100.0 / 50.0 );
get_ros_parameter<float>( nh, "optimization/max_allow_final_cost", m_max_final_cost, 1.0 );
get_ros_parameter<int>( nh, "mapping/init_accumulate_frames", m_mapping_init_accumulate_frames, 50 );
get_ros_parameter<int>( nh, "mapping/maximum_histroy_buffer", m_maximum_history_size, 100 );
get_ros_parameter<int>( nh, "mapping/maximum_mapping_buffer", m_max_buffer_size, 5 );
get_ros_parameter<int>( nh, "mapping/matching_mode", m_matching_mode, 1 );
get_ros_parameter<int>( nh, "mapping/input_downsample_mode", m_if_input_downsample_mode, 1 );
get_ros_parameter<double>( nh, "mapping/maximum_in_fov_angle", m_maximum_in_fov_angle, 30 );
get_ros_parameter<double>( nh, "mapping/maximum_pointcloud_delay_time", m_maximum_pointcloud_delay_time, 0.1 );
get_ros_parameter<double>( nh, "mapping/maximum_in_fov_angle", m_maximum_in_fov_angle, 30 );
get_ros_parameter<double>( nh, "mapping/maximum_search_range_corner", m_maximum_search_range_corner, 100 );
get_ros_parameter<double>( nh, "mapping/maximum_search_range_surface", m_maximum_search_range_surface, 100 );
get_ros_parameter<double>( nh, "mapping/surround_pointcloud_resolution", m_surround_pointcloud_resolution, 0.5 );
get_ros_parameter<int>( nh, "loop_closure/if_enable_loop_closure", m_loop_closure_if_enable, 0 );
get_ros_parameter<int>( nh, "loop_closure/minimum_keyframe_differen", m_loop_closure_minimum_keyframe_differen, 200 );
get_ros_parameter<float>( nh, "loop_closure/minimum_similarity_linear", m_loop_closure_minimum_similarity_linear, 0.65 );
get_ros_parameter<float>( nh, "loop_closure/minimum_similarity_planar", m_loop_closure_minimum_similarity_planar, 0.95 );
get_ros_parameter<float>( nh, "loop_closure/map_alignment_resolution", m_loop_closure_map_alignment_resolution, 0.2 );
get_ros_parameter<float>( nh, "loop_closure/map_alignment_inlier_threshold", m_loop_closure_map_alignment_inlier_threshold, 0.35 );
get_ros_parameter<int>( nh, "loop_closure/map_alignment_maximum_icp_iteration", m_loop_closure_map_alignment_maximum_icp_iteration, 2 );
get_ros_parameter<int>( nh, "loop_closure/maximum_keyframe_in_waiting_list", m_loop_closure_maximum_keyframe_in_wating_list, 3 );
get_ros_parameter<int>( nh, "loop_closure/scans_of_each_keyframe", m_para_scans_of_each_keyframe, 300 );
get_ros_parameter<int>( nh, "loop_closure/scans_between_two_keyframe", m_para_scans_between_two_keyframe, 100 );
get_ros_parameter<int>( nh, "loop_closure/scene_alignment_maximum_residual_block", m_para_scene_alignments_maximum_residual_block, 5000 );
get_ros_parameter<int>( nh, "loop_closure/if_dump_keyframe_data", m_loop_closure_if_dump_keyframe_data, 0 );
get_ros_parameter<int>( nh, "loop_closure/map_alignment_if_dump_matching_result", m_loop_closure_map_alignment_if_dump_matching_result, 0 );
get_ros_parameter<std::string>( nh, "common/log_save_dir", m_log_save_dir_name, "../" );
m_pt_cell_map_full.set_update_mean_and_cov_incrementally( m_if_maps_incre_update_mean_and_cov );
m_logger_common.set_log_dir( m_log_save_dir_name );
m_logger_common.init( "mapping.log" );
m_logger_timer.set_log_dir( m_log_save_dir_name );
m_logger_timer.init( "timer.log" );
m_logger_matching_buff.set_log_dir( m_log_save_dir_name );
m_logger_matching_buff.init( "match_buff.log" );
get_ros_parameter<std::string>( nh, "common/pcd_save_dir", m_pcd_save_dir_name, std::string( "./" ) );
get_ros_parameter<std::string>( nh, "common/loop_save_dir", m_loop_save_dir_name, m_pcd_save_dir_name.append( "_loop" ) );
m_sceene_align.init( m_loop_save_dir_name );
if ( m_if_save_to_pcd_files )
{
m_pcl_tools_aftmap.set_save_dir_name( m_pcd_save_dir_name );
m_pcl_tools_raw.set_save_dir_name( m_pcd_save_dir_name );
}
m_logger_pcd.set_log_dir( m_log_save_dir_name );
m_logger_pcd.init( "poses.log" );
LOG_FILE_LINE( m_logger_common );
*m_logger_common.get_ostream() << m_logger_common.version();
screen_printf( "line resolution %f plane resolution %f \n", m_line_resolution, m_plane_resolution );
m_logger_common.printf( "line resolution %f plane resolution %f \n", m_line_resolution, m_plane_resolution );
m_down_sample_filter_corner.setLeafSize( m_line_resolution, m_line_resolution, m_line_resolution );
m_down_sample_filter_surface.setLeafSize( m_plane_resolution, m_plane_resolution, m_plane_resolution );
m_filter_k_means.setMeanK( m_kmean_filter_count );
m_filter_k_means.setStddevMulThresh( m_kmean_filter_threshold );
}
void laserCloudCornerLastHandler( const sensor_msgs::PointCloud2ConstPtr &laserCloudCornerLast2 )
{
std::unique_lock<std::mutex> lock( m_mutex_buf );
Data_pair * data_pair = get_data_pair( laserCloudCornerLast2->header.stamp.toSec() );
data_pair->add_pc_corner( laserCloudCornerLast2 );
if ( data_pair->is_completed() )
{
m_queue_avail_data.push( data_pair );
}
}
void laserCloudSurfLastHandler( const sensor_msgs::PointCloud2ConstPtr &laserCloudSurfLast2 )
{
std::unique_lock<std::mutex> lock( m_mutex_buf );
Data_pair * data_pair = get_data_pair( laserCloudSurfLast2->header.stamp.toSec() );
data_pair->add_pc_plane( laserCloudSurfLast2 );
if ( data_pair->is_completed() )
{
m_queue_avail_data.push( data_pair );
}
}
void laserCloudFullResHandler( const sensor_msgs::PointCloud2ConstPtr &laserCloudFullRes2 )
{
std::unique_lock<std::mutex> lock( m_mutex_buf );
Data_pair * data_pair = get_data_pair( laserCloudFullRes2->header.stamp.toSec() );
data_pair->add_pc_full( laserCloudFullRes2 );
if ( data_pair->is_completed() )
{
m_queue_avail_data.push( data_pair );
}
}
template <typename T, typename TT>
static void save_mat_to_json_writter( T &writer, const std::string &name, const TT &eigen_mat )
{
writer.Key( name.c_str() ); // output a key,
writer.StartArray(); // Between StartArray()/EndArray(),
for ( size_t i = 0; i < ( size_t )( eigen_mat.cols() * eigen_mat.rows() ); i++ )
writer.Double( eigen_mat( i ) );
writer.EndArray();
}
template <typename T, typename TT>
static void save_quaternion_to_json_writter( T &writer, const std::string &name, const Eigen::Quaternion<TT> &q_curr )
{
writer.Key( name.c_str() );
writer.StartArray();
writer.Double( q_curr.w() );
writer.Double( q_curr.x() );
writer.Double( q_curr.y() );
writer.Double( q_curr.z() );
writer.EndArray();
}
template <typename T, typename TT>
static void save_data_vec_to_json_writter( T &writer, const std::string &name, TT &data_vec )
{
writer.Key( name.c_str() );
writer.StartArray();
for ( auto it = data_vec.begin(); it != data_vec.end(); it++ )
{
writer.Double( *it );
}
writer.EndArray();
}
void dump_pose_and_regerror( std::string file_name, Eigen::Quaterniond &q_curr,
Eigen::Vector3d & t_curr,
std::list<double> ®_err_vec )
{
rapidjson::Document document;
rapidjson::StringBuffer sb;
rapidjson::Writer<rapidjson::StringBuffer> writer( sb );
writer.StartObject();
writer.SetMaxDecimalPlaces( 1000 ); // like set_precision
save_quaternion_to_json_writter( writer, "Q", q_curr );
save_mat_to_json_writter( writer, "T", t_curr );
save_data_vec_to_json_writter( writer, "Reg_err", reg_err_vec );
writer.EndObject();
std::fstream ofs;
ofs.open( file_name.c_str(), std::ios_base::out );
if ( ofs.is_open() )
{
ofs << std::string( sb.GetString() ).c_str();
ofs.close();
}
else
{
for ( int i = 0; i < 109; i++ )
{
screen_out << "Write data to file: " << file_name << " error!!!" << std::endl;
}
}
}
void loop_closure_pub_optimzed_path( const Ceres_pose_graph_3d::MapOfPoses &pose3d_aft_loopclosure )
{
nav_msgs::Odometry odom;
m_laser_after_loopclosure_path.header.stamp = ros::Time::now();
m_laser_after_loopclosure_path.header.frame_id = "camera_init";
for ( auto it = pose3d_aft_loopclosure.begin();
it != pose3d_aft_loopclosure.end(); it++ )
{
geometry_msgs::PoseStamped pose_stamp;
Ceres_pose_graph_3d::Pose3d pose_3d = it->second;
pose_stamp.pose.orientation.x = pose_3d.q.x();
pose_stamp.pose.orientation.y = pose_3d.q.y();
pose_stamp.pose.orientation.z = pose_3d.q.z();
pose_stamp.pose.orientation.w = pose_3d.q.w();
pose_stamp.pose.position.x = pose_3d.p( 0 );
pose_stamp.pose.position.y = pose_3d.p( 1 );
pose_stamp.pose.position.z = pose_3d.p( 2 );
pose_stamp.header.frame_id = "camera_init";
m_laser_after_loopclosure_path.poses.push_back( pose_stamp );
}
m_pub_laser_aft_loopclosure_path.publish( m_laser_after_loopclosure_path );
}
//ANCHOR loop_detection
void service_loop_detection()
{
int last_update_index = 0;
sensor_msgs::PointCloud2 ros_laser_cloud_surround;
pcl::PointCloud<PointType> pt_full;
Eigen::Quaterniond q_curr;
Eigen::Vector3d t_curr;
std::list<double> reg_error_his;
std::string json_file_name;
int curren_frame_idx;
std::vector<std::shared_ptr<Maps_keyframe<float>>> keyframe_vec;
Mapping_refine<PointType> map_rfn;
std::vector<std::string> m_filename_vec;
std::map<int, std::string> map_file_name;
Ceres_pose_graph_3d::MapOfPoses pose3d_map, pose3d_map_ori;
Ceres_pose_graph_3d::VectorOfPose pose3d_vec;
Ceres_pose_graph_3d::VectorOfConstraints constrain_vec;
float avail_ratio_plane = 0.05; // 0.05 for 300 scans, 0.15 for 1000 scans
float avail_ratio_line = 0.03;
m_scene_align.init( m_loop_save_dir_name );
m_scene_align.m_accepted_threshold = m_loop_closure_map_alignment_inlier_threshold;
m_scene_align.m_maximum_icp_iteration = m_loop_closure_map_alignment_maximum_icp_iteration;
// scene_align. = m_
PCL_TOOLS::PCL_point_cloud_to_pcd pcd_saver;
pcd_saver.set_save_dir_name( std::string( m_loop_save_dir_name ).append( "/pcd" ) );
map_rfn.set_save_dir( std::string( m_loop_save_dir_name ).append( "/mapping_refined" ) );
map_rfn.set_down_sample_resolution( 0.2 );
std::map<int, pcl::PointCloud<PointType>> map_id_pc;
int if_end = 0;
pcl::VoxelGrid<PointType> down_sample_filter;
m_logger_loop_closure.set_log_dir(m_log_save_dir_name);
m_logger_loop_closure.init( "loop_closure.log" );
down_sample_filter.setLeafSize( m_surround_pointcloud_resolution, m_surround_pointcloud_resolution, m_surround_pointcloud_resolution );
while ( 1 )
{
std::this_thread::sleep_for( std::chrono::milliseconds( 1 ) );
//m_mutex_dump_full_history.lock();
if ( m_keyframe_need_precession_list.size() == 0 )
{
continue;
}
m_timer.tic( "New keyframe" );
q_curr = m_keyframe_need_precession_list.front()->m_pose_q;
t_curr = m_keyframe_need_precession_list.front()->m_pose_t;
// q_curr = m_q_w_curr;
// t_curr = m_t_w_curr;
reg_error_his = m_his_reg_error;
m_keyframe_need_precession_list.front()->update_features_of_each_cells();
m_keyframe_need_precession_list.front()->analyze();
keyframe_vec.push_back( m_keyframe_need_precession_list.front() );
m_mutex_keyframe.lock();
m_keyframe_need_precession_list.pop_front();
m_mutex_keyframe.unlock();
curren_frame_idx = keyframe_vec.back()->m_ending_frame_idx;
if ( 1 )
{
down_sample_filter.setInputCloud( keyframe_vec.back()->m_accumulated_point_cloud.makeShared() );
down_sample_filter.filter( keyframe_vec.back()->m_accumulated_point_cloud );
}
map_id_pc.insert( std::make_pair( map_id_pc.size(), keyframe_vec.back()->m_accumulated_point_cloud ) );
pose3d_vec.push_back( Ceres_pose_graph_3d::Pose3d( q_curr, t_curr ) );
pose3d_map.insert( std::make_pair( pose3d_map.size(), Ceres_pose_graph_3d::Pose3d( q_curr, t_curr ) ) );
if ( pose3d_vec.size() >= 2 )
{
Ceres_pose_graph_3d::Constraint3d temp_csn;
Eigen::Vector3d relative_T = pose3d_vec[ pose3d_vec.size() - 2 ].q.inverse() * ( t_curr - pose3d_vec[ pose3d_vec.size() - 2 ].p );
Eigen::Quaterniond relative_Q = pose3d_vec[ pose3d_vec.size() - 2 ].q.inverse() * q_curr;
temp_csn = Ceres_pose_graph_3d::Constraint3d( pose3d_vec.size() - 2, pose3d_vec.size() - 1,
relative_Q, relative_T );
constrain_vec.push_back( temp_csn );
}
// Save pose
json_file_name = std::string( m_loop_save_dir_name ).append( "/pose_" ).append( std::to_string( curren_frame_idx ) ).append( ".json" );
dump_pose_and_regerror( json_file_name, q_curr, t_curr, reg_error_his );
last_update_index = m_current_frame_index;
m_timer.tic( "Find loop" );
std::shared_ptr<Maps_keyframe<float>> last_keyframe = keyframe_vec.back();
float ratio_non_zero_plane = last_keyframe->m_ratio_nonzero_plane;
float ratio_non_zero_line = last_keyframe->m_ratio_nonzero_line;
if ( m_loop_closure_if_dump_keyframe_data ) // Dump points cloud data
{
json_file_name = std::string( "keyframe_" ).append( std::to_string( curren_frame_idx ) ).append( ".json" );
last_keyframe->save_to_file( std::string( m_loop_save_dir_name ), json_file_name ); // Save keyframe data
pcd_saver.save_to_pcd_files( "pcd", pt_full, curren_frame_idx ); // Save to pcd files
}
map_file_name.insert( std::make_pair( map_file_name.size(), std::string( m_loop_save_dir_name ).append( "/" ).append( json_file_name ) ) );
m_filename_vec.push_back( std::string( m_loop_save_dir_name ).append( "/" ).append( json_file_name ) );
float sim_plane_res_cv = 0, sim_plane_res = 0;
float sim_line_res_cv = 0, sim_line_res = 0;
float sim_plane_res_roi = 0, sim_line_res_roi = 0;
m_logger_loop_closure.printf( "--- Current_idx = %d, lidar_frame_idx = %d ---\r\n", keyframe_vec.size(), curren_frame_idx );
m_logger_loop_closure.printf( "%s", last_keyframe->get_frame_info().c_str() );
for ( size_t his = 0; his < keyframe_vec.size() - 1; his++ )
{
if ( if_end )
{
break;
}
if ( keyframe_vec.size() - his < ( size_t ) m_loop_closure_minimum_keyframe_differen )
{
continue;
}
float ratio_non_zero_plane_his = keyframe_vec[ his ]->m_ratio_nonzero_plane;
float ratio_non_zero_line_his = keyframe_vec[ his ]->m_ratio_nonzero_line;