-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathlaserMapping.cpp
More file actions
1158 lines (1021 loc) · 50 KB
/
laserMapping.cpp
File metadata and controls
1158 lines (1021 loc) · 50 KB
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 dev@livoxtech.com
// 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 <omp.h>
#include <mutex>
#include <math.h>
#include <thread>
#include <fstream>
#include <csignal>
#include <chrono>
#include <unistd.h>
#include <Python.h>
#include <so3_math.h>
#include <rclcpp/rclcpp.hpp>
#include <Eigen/Core>
#include "IMU_Processing.hpp"
#include <nav_msgs/msg/odometry.hpp>
#include <nav_msgs/msg/path.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/io/pcd_io.h>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <std_srvs/srv/trigger.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <geometry_msgs/msg/vector3.hpp>
#include <livox_ros_driver2/msg/custom_msg.hpp>
#include "preprocess.h"
#include <ikd-Tree/ikd_Tree.h>
#define INIT_TIME (0.1)
#define LASER_POINT_COV (0.001)
#define MAXN (720000)
#define PUBFRAME_PERIOD (20)
#ifndef ROOT_DIR
#define ROOT_DIR "../"
#endif
/*** Time Log Variables ***/
double kdtree_incremental_time = 0.0, kdtree_search_time = 0.0, kdtree_delete_time = 0.0;
double T1[MAXN], s_plot[MAXN], s_plot2[MAXN], s_plot3[MAXN], s_plot4[MAXN], s_plot5[MAXN], s_plot6[MAXN], s_plot7[MAXN], s_plot8[MAXN], s_plot9[MAXN], s_plot10[MAXN], s_plot11[MAXN];
double match_time = 0, solve_time = 0, solve_const_H_time = 0;
int kdtree_size_st = 0, kdtree_size_end = 0, add_point_size = 0, kdtree_delete_counter = 0;
bool runtime_pos_log = false, pcd_save_en = false, time_sync_en = false, extrinsic_est_en = true, path_en = true;
/**************************/
float res_last[100000] = {0.0};
float DET_RANGE = 300.0f;
const float MOV_THRESHOLD = 1.5f;
double time_diff_lidar_to_imu = 0.0;
mutex mtx_buffer;
condition_variable sig_buffer;
string root_dir = ROOT_DIR;
string map_file_path, lid_topic, imu_topic;
double res_mean_last = 0.05, total_residual = 0.0;
double last_timestamp_lidar = 0, last_timestamp_imu = -1.0;
double gyr_cov = 0.1, acc_cov = 0.1, b_gyr_cov = 0.0001, b_acc_cov = 0.0001;
double filter_size_corner_min = 0, filter_size_surf_min = 0, filter_size_map_min = 0, fov_deg = 0;
double cube_len = 0, HALF_FOV_COS = 0, FOV_DEG = 0, total_distance = 0, lidar_end_time = 0, first_lidar_time = 0.0;
int effct_feat_num = 0, time_log_counter = 0, scan_count = 0, publish_count = 0;
int iterCount = 0, feats_down_size = 0, NUM_MAX_ITERATIONS = 0, laserCloudValidNum = 0, pcd_save_interval = -1, pcd_index = 0;
bool point_selected_surf[100000] = {0};
bool lidar_pushed, flg_first_scan = true, flg_exit = false, flg_EKF_inited;
bool scan_pub_en = false, dense_pub_en = false, scan_body_pub_en = false;
bool is_first_lidar = true;
vector<vector<int>> pointSearchInd_surf;
vector<BoxPointType> cub_needrm;
vector<PointVector> Nearest_Points;
vector<double> extrinT(3, 0.0);
vector<double> extrinR(9, 0.0);
deque<double> time_buffer;
deque<PointCloudXYZI::Ptr> lidar_buffer;
deque<sensor_msgs::msg::Imu::ConstSharedPtr> imu_buffer;
PointCloudXYZI::Ptr featsFromMap(new PointCloudXYZI());
PointCloudXYZI::Ptr feats_undistort(new PointCloudXYZI());
PointCloudXYZI::Ptr feats_down_body(new PointCloudXYZI());
PointCloudXYZI::Ptr feats_down_world(new PointCloudXYZI());
PointCloudXYZI::Ptr normvec(new PointCloudXYZI(100000, 1));
PointCloudXYZI::Ptr laserCloudOri(new PointCloudXYZI(100000, 1));
PointCloudXYZI::Ptr corr_normvect(new PointCloudXYZI(100000, 1));
PointCloudXYZI::Ptr _featsArray;
pcl::VoxelGrid<PointType> downSizeFilterSurf;
pcl::VoxelGrid<PointType> downSizeFilterMap;
KD_TREE<PointType> ikdtree;
V3F XAxisPoint_body(LIDAR_SP_LEN, 0.0, 0.0);
V3F XAxisPoint_world(LIDAR_SP_LEN, 0.0, 0.0);
V3D euler_cur;
V3D position_last(Zero3d);
V3D Lidar_T_wrt_IMU(Zero3d);
M3D Lidar_R_wrt_IMU(Eye3d);
/*** EKF inputs and output ***/
MeasureGroup Measures;
esekfom::esekf<state_ikfom, 12, input_ikfom> kf;
state_ikfom state_point;
vect3 pos_lid;
nav_msgs::msg::Path path;
nav_msgs::msg::Odometry odomAftMapped;
geometry_msgs::msg::Quaternion geoQuat;
geometry_msgs::msg::PoseStamped msg_body_pose;
shared_ptr<Preprocess> p_pre(new Preprocess());
shared_ptr<ImuProcess> p_imu(new ImuProcess());
void SigHandle(int sig)
{
flg_exit = true;
std::cout << "catch sig %d" << sig << std::endl;
sig_buffer.notify_all();
rclcpp::shutdown();
}
inline void dump_lio_state_to_log(FILE *fp)
{
V3D rot_ang(Log(state_point.rot.toRotationMatrix()));
fprintf(fp, "%lf ", Measures.lidar_beg_time - first_lidar_time);
fprintf(fp, "%lf %lf %lf ", rot_ang(0), rot_ang(1), rot_ang(2)); // Angle
fprintf(fp, "%lf %lf %lf ", state_point.pos(0), state_point.pos(1), state_point.pos(2)); // Pos
fprintf(fp, "%lf %lf %lf ", 0.0, 0.0, 0.0); // omega
fprintf(fp, "%lf %lf %lf ", state_point.vel(0), state_point.vel(1), state_point.vel(2)); // Vel
fprintf(fp, "%lf %lf %lf ", 0.0, 0.0, 0.0); // Acc
fprintf(fp, "%lf %lf %lf ", state_point.bg(0), state_point.bg(1), state_point.bg(2)); // Bias_g
fprintf(fp, "%lf %lf %lf ", state_point.ba(0), state_point.ba(1), state_point.ba(2)); // Bias_a
fprintf(fp, "%lf %lf %lf ", state_point.grav[0], state_point.grav[1], state_point.grav[2]); // Bias_a
fprintf(fp, "\r\n");
fflush(fp);
}
void pointBodyToWorld_ikfom(PointType const * const pi, PointType * const po, state_ikfom &s)
{
V3D p_body(pi->x, pi->y, pi->z);
V3D p_global(s.rot * (s.offset_R_L_I*p_body + s.offset_T_L_I) + s.pos);
po->x = p_global(0);
po->y = p_global(1);
po->z = p_global(2);
po->intensity = pi->intensity;
}
void pointBodyToWorld(PointType const * const pi, PointType * const po)
{
V3D p_body(pi->x, pi->y, pi->z);
V3D p_global(state_point.rot * (state_point.offset_R_L_I*p_body + state_point.offset_T_L_I) + state_point.pos);
po->x = p_global(0);
po->y = p_global(1);
po->z = p_global(2);
po->intensity = pi->intensity;
}
template<typename T>
void pointBodyToWorld(const Matrix<T, 3, 1> &pi, Matrix<T, 3, 1> &po)
{
V3D p_body(pi[0], pi[1], pi[2]);
V3D p_global(state_point.rot * (state_point.offset_R_L_I*p_body + state_point.offset_T_L_I) + state_point.pos);
po[0] = p_global(0);
po[1] = p_global(1);
po[2] = p_global(2);
}
void RGBpointBodyToWorld(PointType const * const pi, PointType * const po)
{
V3D p_body(pi->x, pi->y, pi->z);
V3D p_global(state_point.rot * (state_point.offset_R_L_I*p_body + state_point.offset_T_L_I) + state_point.pos);
po->x = p_global(0);
po->y = p_global(1);
po->z = p_global(2);
po->intensity = pi->intensity;
}
void RGBpointBodyLidarToIMU(PointType const * const pi, PointType * const po)
{
V3D p_body_lidar(pi->x, pi->y, pi->z);
V3D p_body_imu(state_point.offset_R_L_I*p_body_lidar + state_point.offset_T_L_I);
po->x = p_body_imu(0);
po->y = p_body_imu(1);
po->z = p_body_imu(2);
po->intensity = pi->intensity;
}
void points_cache_collect()
{
PointVector points_history;
ikdtree.acquire_removed_points(points_history);
// for (int i = 0; i < points_history.size(); i++) _featsArray->push_back(points_history[i]);
}
BoxPointType LocalMap_Points;
bool Localmap_Initialized = false;
// 维护局部地图边界,随着无人机运动滑动地图边界,删除超出边界的点云数据
void lasermap_fov_segment()
{
cub_needrm.clear();
kdtree_delete_counter = 0;
kdtree_delete_time = 0.0;
pointBodyToWorld(XAxisPoint_body, XAxisPoint_world);
V3D pos_LiD = pos_lid;
// 若还没初始化局部地图,则以当前位置为中心初始化一个立方体范围vertex_min/max为对角点)
if (!Localmap_Initialized){
for (int i = 0; i < 3; i++){
LocalMap_Points.vertex_min[i] = pos_LiD(i) - cube_len / 2.0;
LocalMap_Points.vertex_max[i] = pos_LiD(i) + cube_len / 2.0;
}
Localmap_Initialized = true;
return;
}
float dist_to_map_edge[3][2];
bool need_move = false;
// 第一帧之后,判断与第一帧之间距离是否过近,若是则触发地图滑动
for (int i = 0; i < 3; i++){
dist_to_map_edge[i][0] = fabs(pos_LiD(i) - LocalMap_Points.vertex_min[i]);
dist_to_map_edge[i][1] = fabs(pos_LiD(i) - LocalMap_Points.vertex_max[i]);
if (dist_to_map_edge[i][0] <= MOV_THRESHOLD * DET_RANGE || dist_to_map_edge[i][1] <= MOV_THRESHOLD * DET_RANGE) need_move = true;
}
if (!need_move) return;
BoxPointType New_LocalMap_Points, tmp_boxpoints;
New_LocalMap_Points = LocalMap_Points;
// 计算滑动距离,保证滑动后地图边界能覆盖当前位置且地图大小保持合理
float mov_dist = max((cube_len - 2.0 * MOV_THRESHOLD * DET_RANGE) * 0.5 * 0.9, double(DET_RANGE * (MOV_THRESHOLD -1)));
for (int i = 0; i < 3; i++){
tmp_boxpoints = LocalMap_Points;
// 若靠近最小边界,地图整体沿负方向滑动,同时标记滑出区域,准备删除点云
if (dist_to_map_edge[i][0] <= MOV_THRESHOLD * DET_RANGE){
New_LocalMap_Points.vertex_max[i] -= mov_dist;
New_LocalMap_Points.vertex_min[i] -= mov_dist;
tmp_boxpoints.vertex_min[i] = LocalMap_Points.vertex_max[i] - mov_dist;
cub_needrm.push_back(tmp_boxpoints);
// 若靠近最大边界,地图整体沿正方向滑动,同时标记滑出区域,准备删除点云
} else if (dist_to_map_edge[i][1] <= MOV_THRESHOLD * DET_RANGE){
New_LocalMap_Points.vertex_max[i] += mov_dist;
New_LocalMap_Points.vertex_min[i] += mov_dist;
tmp_boxpoints.vertex_max[i] = LocalMap_Points.vertex_min[i] + mov_dist;
cub_needrm.push_back(tmp_boxpoints);
}
}
LocalMap_Points = New_LocalMap_Points;
points_cache_collect();
double delete_begin = omp_get_wtime();
if(cub_needrm.size() > 0) kdtree_delete_counter = ikdtree.Delete_Point_Boxes(cub_needrm);
kdtree_delete_time = omp_get_wtime() - delete_begin;
}
double timediff_lidar_wrt_imu = 0.0;
bool timediff_set_flg = false;
void livox_pcl_cbk(const livox_ros_driver2::msg::CustomMsg::UniquePtr msg)
{
mtx_buffer.lock();
double cur_time = get_time_sec(msg->header.stamp);
double preprocess_start_time = omp_get_wtime();
scan_count ++;
if (!is_first_lidar && cur_time < last_timestamp_lidar)
{
std::cerr << "lidar loop back, clear buffer" << std::endl;
lidar_buffer.clear();
}
if(is_first_lidar)
{
is_first_lidar = false;
}
last_timestamp_lidar = cur_time;
if (!time_sync_en && abs(last_timestamp_imu - last_timestamp_lidar) > 10.0 && !imu_buffer.empty() && !lidar_buffer.empty() )
{
printf("IMU and LiDAR not Synced, IMU time: %lf, lidar header time: %lf \n",last_timestamp_imu, last_timestamp_lidar);
}
if (time_sync_en && !timediff_set_flg && abs(last_timestamp_lidar - last_timestamp_imu) > 1 && !imu_buffer.empty())
{
timediff_set_flg = true;
timediff_lidar_wrt_imu = last_timestamp_lidar + 0.1 - last_timestamp_imu;
printf("Self sync IMU and LiDAR, time diff is %.10lf \n", timediff_lidar_wrt_imu);
}
PointCloudXYZI::Ptr ptr(new PointCloudXYZI());
p_pre->process(msg, ptr);
lidar_buffer.push_back(ptr);
time_buffer.push_back(last_timestamp_lidar);
s_plot11[scan_count] = omp_get_wtime() - preprocess_start_time;
mtx_buffer.unlock();
sig_buffer.notify_all();
}
void imu_cbk(const sensor_msgs::msg::Imu::UniquePtr msg_in)
{
publish_count ++;
// cout<<"IMU got at: "<<msg_in->header.stamp.toSec()<<endl;
sensor_msgs::msg::Imu::SharedPtr msg(new sensor_msgs::msg::Imu(*msg_in));
msg->header.stamp = get_ros_time(get_time_sec(msg_in->header.stamp) - time_diff_lidar_to_imu);
if (abs(timediff_lidar_wrt_imu) > 0.1 && time_sync_en)
{
msg->header.stamp = \
rclcpp::Time(timediff_lidar_wrt_imu + get_time_sec(msg_in->header.stamp));
}
double timestamp = get_time_sec(msg->header.stamp);
mtx_buffer.lock();
if (timestamp < last_timestamp_imu)
{
std::cerr << "lidar loop back, clear buffer" << std::endl;
imu_buffer.clear();
}
last_timestamp_imu = timestamp;
imu_buffer.push_back(msg);
mtx_buffer.unlock();
sig_buffer.notify_all();
}
double lidar_mean_scantime = 0.0;
int scan_num = 0;
bool sync_packages(MeasureGroup &meas)
{
if (lidar_buffer.empty() || imu_buffer.empty()) {
return false;
}
/*** push a lidar scan ***/
if(!lidar_pushed)
{
meas.lidar = lidar_buffer.front();
meas.lidar_beg_time = time_buffer.front();
if (meas.lidar->points.size() <= 1) // time too little
{
lidar_end_time = meas.lidar_beg_time + lidar_mean_scantime;
std::cerr << "Too few input point cloud!\n";
}
else if (meas.lidar->points.back().curvature / double(1000) < 0.5 * lidar_mean_scantime)
{
lidar_end_time = meas.lidar_beg_time + lidar_mean_scantime;
}
else
{
scan_num ++;
lidar_end_time = meas.lidar_beg_time + meas.lidar->points.back().curvature / double(1000);
lidar_mean_scantime += (meas.lidar->points.back().curvature / double(1000) - lidar_mean_scantime) / scan_num;
}
meas.lidar_end_time = lidar_end_time;
lidar_pushed = true;
}
if (last_timestamp_imu < lidar_end_time)
{
return false;
}
/*** push imu data, and pop from imu buffer ***/
double imu_time = get_time_sec(imu_buffer.front()->header.stamp);
meas.imu.clear();
while ((!imu_buffer.empty()) && (imu_time < lidar_end_time))
{
imu_time = get_time_sec(imu_buffer.front()->header.stamp);
if(imu_time > lidar_end_time) break;
meas.imu.push_back(imu_buffer.front());
imu_buffer.pop_front();
}
lidar_buffer.pop_front();
time_buffer.pop_front();
lidar_pushed = false;
return true;
}
int process_increments = 0;
// 坐标变化+体素滤波+将新点加入地图
void map_incremental()
{
PointVector PointToAdd;
PointVector PointNoNeedDownsample;
// 提前为 vector 分配足够的内存容量
PointToAdd.reserve(feats_down_size);
PointNoNeedDownsample.reserve(feats_down_size);
for (int i = 0; i < feats_down_size; i++)
{
/* transform to world frame */
// 将当前帧激光雷达点从雷达自身坐标系(Body 坐标系)转换到世界坐标系(World frame)。
pointBodyToWorld(&(feats_down_body->points[i]), &(feats_down_world->points[i]));
/* decide if need add to map */
if (!Nearest_Points[i].empty() && flg_EKF_inited)
{
const PointVector &points_near = Nearest_Points[i];
bool need_add = true;
BoxPointType Box_of_Point;
PointType downsample_result, mid_point;
//将点存入体素中心
mid_point.x = floor(feats_down_world->points[i].x/filter_size_map_min)*filter_size_map_min + 0.5 * filter_size_map_min;
mid_point.y = floor(feats_down_world->points[i].y/filter_size_map_min)*filter_size_map_min + 0.5 * filter_size_map_min;
mid_point.z = floor(feats_down_world->points[i].z/filter_size_map_min)*filter_size_map_min + 0.5 * filter_size_map_min;
float dist = calc_dist(feats_down_world->points[i],mid_point);
if (fabs(points_near[0].x - mid_point.x) > 0.5 * filter_size_map_min && fabs(points_near[0].y - mid_point.y) > 0.5 * filter_size_map_min && fabs(points_near[0].z - mid_point.z) > 0.5 * filter_size_map_min){
PointNoNeedDownsample.push_back(feats_down_world->points[i]);
continue;
}
for (int readd_i = 0; readd_i < NUM_MATCH_POINTS; readd_i ++)
{
// 如果最近邻点在别的 voxel, 则当前点是这个 voxel 中的唯一候选点
// 因为kd-tree,points_near[0]就是最近点
if (points_near.size() < NUM_MATCH_POINTS) break;
if (calc_dist(points_near[readd_i], mid_point) < dist)
{
need_add = false;
break;
}
}
// 如果周围点比当前点更近
if (need_add) PointToAdd.push_back(feats_down_world->points[i]);
}
else
{
PointToAdd.push_back(feats_down_world->points[i]);
}
}
double st_time = omp_get_wtime();
add_point_size = ikdtree.Add_Points(PointToAdd, true);
ikdtree.Add_Points(PointNoNeedDownsample, false);
add_point_size = PointToAdd.size() + PointNoNeedDownsample.size();
kdtree_incremental_time = omp_get_wtime() - st_time;
}
PointCloudXYZI::Ptr pcl_wait_pub(new PointCloudXYZI());
PointCloudXYZI::Ptr pcl_wait_save(new PointCloudXYZI());
void publish_frame_world(rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pubLaserCloudFull)
{
if(scan_pub_en)
{
PointCloudXYZI::Ptr laserCloudFullRes(dense_pub_en ? feats_undistort : feats_down_body);
int size = laserCloudFullRes->points.size();
PointCloudXYZI::Ptr laserCloudWorld( \
new PointCloudXYZI(size, 1));
for (int i = 0; i < size; i++)
{
RGBpointBodyToWorld(&laserCloudFullRes->points[i], \
&laserCloudWorld->points[i]);
}
sensor_msgs::msg::PointCloud2 laserCloudmsg;
pcl::toROSMsg(*laserCloudWorld, laserCloudmsg);
// laserCloudmsg.header.stamp = ros::Time().fromSec(lidar_end_time);
laserCloudmsg.header.stamp = get_ros_time(lidar_end_time);
laserCloudmsg.header.frame_id = "camera_init";
pubLaserCloudFull->publish(laserCloudmsg);
publish_count -= PUBFRAME_PERIOD;
}
}
void publish_frame_body(rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pubLaserCloudFull_body)
{
int size = feats_undistort->points.size();
PointCloudXYZI::Ptr laserCloudIMUBody(new PointCloudXYZI(size, 1));
for (int i = 0; i < size; i++)
{
RGBpointBodyLidarToIMU(&feats_undistort->points[i], \
&laserCloudIMUBody->points[i]);
}
sensor_msgs::msg::PointCloud2 laserCloudmsg;
pcl::toROSMsg(*laserCloudIMUBody, laserCloudmsg);
laserCloudmsg.header.stamp = get_ros_time(lidar_end_time);
laserCloudmsg.header.frame_id = "body";
pubLaserCloudFull_body->publish(laserCloudmsg);
publish_count -= PUBFRAME_PERIOD;
}
void publish_effect_world(rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pubLaserCloudEffect)
{
PointCloudXYZI::Ptr laserCloudWorld( \
new PointCloudXYZI(effct_feat_num, 1));
for (int i = 0; i < effct_feat_num; i++)
{
RGBpointBodyToWorld(&laserCloudOri->points[i], \
&laserCloudWorld->points[i]);
}
sensor_msgs::msg::PointCloud2 laserCloudFullRes3;
pcl::toROSMsg(*laserCloudWorld, laserCloudFullRes3);
laserCloudFullRes3.header.stamp = get_ros_time(lidar_end_time);
laserCloudFullRes3.header.frame_id = "camera_init";
pubLaserCloudEffect->publish(laserCloudFullRes3);
}
void publish_map(rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pubLaserCloudMap)
{
PointCloudXYZI::Ptr laserCloudFullRes(dense_pub_en ? feats_undistort : feats_down_body);
int size = laserCloudFullRes->points.size();
PointCloudXYZI::Ptr laserCloudWorld( \
new PointCloudXYZI(size, 1));
for (int i = 0; i < size; i++)
{
RGBpointBodyToWorld(&laserCloudFullRes->points[i], \
&laserCloudWorld->points[i]);
}
*pcl_wait_pub += *laserCloudWorld;
sensor_msgs::msg::PointCloud2 laserCloudmsg;
pcl::toROSMsg(*pcl_wait_pub, laserCloudmsg);
// laserCloudmsg.header.stamp = ros::Time().fromSec(lidar_end_time);
laserCloudmsg.header.stamp = get_ros_time(lidar_end_time);
laserCloudmsg.header.frame_id = "camera_init";
pubLaserCloudMap->publish(laserCloudmsg);
// sensor_msgs::msg::PointCloud2 laserCloudMap;
// pcl::toROSMsg(*featsFromMap, laserCloudMap);
// laserCloudMap.header.stamp = get_ros_time(lidar_end_time);
// laserCloudMap.header.frame_id = "camera_init";
// pubLaserCloudMap->publish(laserCloudMap);
}
void save_to_pcd()
{
pcl::PCDWriter pcd_writer;
pcd_writer.writeBinary(map_file_path, *pcl_wait_pub);
}
template<typename T>
void set_posestamp(T & out)
{
out.pose.position.x = state_point.pos(0);
out.pose.position.y = state_point.pos(1);
out.pose.position.z = state_point.pos(2);
out.pose.orientation.x = geoQuat.x;
out.pose.orientation.y = geoQuat.y;
out.pose.orientation.z = geoQuat.z;
out.pose.orientation.w = geoQuat.w;
}
void publish_odometry(const rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pubOdomAftMapped, std::unique_ptr<tf2_ros::TransformBroadcaster> & tf_br)
{
odomAftMapped.header.frame_id = "camera_init";
odomAftMapped.child_frame_id = "body";
odomAftMapped.header.stamp = get_ros_time(lidar_end_time);
set_posestamp(odomAftMapped.pose);
pubOdomAftMapped->publish(odomAftMapped);
auto P = kf.get_P();
for (int i = 0; i < 6; i ++)
{
int k = i < 3 ? i + 3 : i - 3;
odomAftMapped.pose.covariance[i*6 + 0] = P(k, 3);
odomAftMapped.pose.covariance[i*6 + 1] = P(k, 4);
odomAftMapped.pose.covariance[i*6 + 2] = P(k, 5);
odomAftMapped.pose.covariance[i*6 + 3] = P(k, 0);
odomAftMapped.pose.covariance[i*6 + 4] = P(k, 1);
odomAftMapped.pose.covariance[i*6 + 5] = P(k, 2);
}
geometry_msgs::msg::TransformStamped trans;
trans.header.frame_id = "camera_init";
trans.header.stamp = odomAftMapped.header.stamp;
trans.child_frame_id = "body";
trans.transform.translation.x = odomAftMapped.pose.pose.position.x;
trans.transform.translation.y = odomAftMapped.pose.pose.position.y;
trans.transform.translation.z = odomAftMapped.pose.pose.position.z;
trans.transform.rotation.w = odomAftMapped.pose.pose.orientation.w;
trans.transform.rotation.x = odomAftMapped.pose.pose.orientation.x;
trans.transform.rotation.y = odomAftMapped.pose.pose.orientation.y;
trans.transform.rotation.z = odomAftMapped.pose.pose.orientation.z;
tf_br->sendTransform(trans);
}
void publish_path(rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr pubPath)
{
set_posestamp(msg_body_pose);
msg_body_pose.header.stamp = get_ros_time(lidar_end_time); // ros::Time().fromSec(lidar_end_time);
msg_body_pose.header.frame_id = "camera_init";
/*** if path is too large, the rvis will crash ***/
static int jjj = 0;
jjj++;
if (jjj % 10 == 0)
{
path.poses.push_back(msg_body_pose);
pubPath->publish(path);
}
}
void h_share_model(state_ikfom &s, esekfom::dyn_share_datastruct<double> &ekfom_data)
{
double match_start = omp_get_wtime();
laserCloudOri->clear();
corr_normvect->clear();
total_residual = 0.0;
/** closest surface search and residual computation **/
#ifdef MP_EN
omp_set_num_threads(MP_PROC_NUM);
#pragma omp parallel for
#endif
for (int i = 0; i < feats_down_size; i++)
{
PointType &point_body = feats_down_body->points[i];
PointType &point_world = feats_down_world->points[i];
/* transform to world frame */
V3D p_body(point_body.x, point_body.y, point_body.z);
V3D p_global(s.rot * (s.offset_R_L_I*p_body + s.offset_T_L_I) + s.pos);
point_world.x = p_global(0);
point_world.y = p_global(1);
point_world.z = p_global(2);
point_world.intensity = point_body.intensity;
vector<float> pointSearchSqDis(NUM_MATCH_POINTS);
auto &points_near = Nearest_Points[i];
if (ekfom_data.converge)
{
/** Find the closest surfaces in the map **/
ikdtree.Nearest_Search(point_world, NUM_MATCH_POINTS, points_near, pointSearchSqDis);
point_selected_surf[i] = points_near.size() < NUM_MATCH_POINTS ? false : pointSearchSqDis[NUM_MATCH_POINTS - 1] > 5 ? false : true;
}
if (!point_selected_surf[i]) continue;
VF(4) pabcd;
point_selected_surf[i] = false;
if (esti_plane(pabcd, points_near, 0.1f))
{
float pd2 = pabcd(0) * point_world.x + pabcd(1) * point_world.y + pabcd(2) * point_world.z + pabcd(3);
float s = 1 - 0.9 * fabs(pd2) / sqrt(p_body.norm());
if (s > 0.9)
{
point_selected_surf[i] = true;
normvec->points[i].x = pabcd(0);
normvec->points[i].y = pabcd(1);
normvec->points[i].z = pabcd(2);
normvec->points[i].intensity = pd2;
res_last[i] = abs(pd2);
}
}
}
effct_feat_num = 0;
for (int i = 0; i < feats_down_size; i++)
{
if (point_selected_surf[i])
{
laserCloudOri->points[effct_feat_num] = feats_down_body->points[i];
corr_normvect->points[effct_feat_num] = normvec->points[i];
total_residual += res_last[i];
effct_feat_num ++;
}
}
if (effct_feat_num < 1)
{
ekfom_data.valid = false;
std::cerr << "No Effective Points!" << std::endl;
// ROS_WARN("No Effective Points! \n");
return;
}
res_mean_last = total_residual / effct_feat_num;
match_time += omp_get_wtime() - match_start;
double solve_start_ = omp_get_wtime();
/*** Computation of Measuremnt Jacobian matrix H and measurents vector ***/
ekfom_data.h_x = MatrixXd::Zero(effct_feat_num, 12); //23
ekfom_data.h.resize(effct_feat_num);
for (int i = 0; i < effct_feat_num; i++)
{
const PointType &laser_p = laserCloudOri->points[i];
V3D point_this_be(laser_p.x, laser_p.y, laser_p.z);
M3D point_be_crossmat;
point_be_crossmat << SKEW_SYM_MATRX(point_this_be);
V3D point_this = s.offset_R_L_I * point_this_be + s.offset_T_L_I;
M3D point_crossmat;
point_crossmat<<SKEW_SYM_MATRX(point_this);
/*** get the normal vector of closest surface/corner ***/
const PointType &norm_p = corr_normvect->points[i];
V3D norm_vec(norm_p.x, norm_p.y, norm_p.z);
/*** calculate the Measuremnt Jacobian matrix H ***/
V3D C(s.rot.conjugate() *norm_vec);
V3D A(point_crossmat * C);
if (extrinsic_est_en)
{
V3D B(point_be_crossmat * s.offset_R_L_I.conjugate() * C); //s.rot.conjugate()*norm_vec);
ekfom_data.h_x.block<1, 12>(i,0) << norm_p.x, norm_p.y, norm_p.z, VEC_FROM_ARRAY(A), VEC_FROM_ARRAY(B), VEC_FROM_ARRAY(C);
}
else
{
ekfom_data.h_x.block<1, 12>(i,0) << norm_p.x, norm_p.y, norm_p.z, VEC_FROM_ARRAY(A), 0.0, 0.0, 0.0, 0.0, 0.0, 0.0;
}
/*** Measuremnt: distance to the closest surface/corner ***/
ekfom_data.h(i) = -norm_p.intensity;
}
solve_time += omp_get_wtime() - solve_start_;
}
class LaserMappingNode : public rclcpp::Node
{
public:
LaserMappingNode(const rclcpp::NodeOptions& options = rclcpp::NodeOptions()) : Node("laser_mapping", options)
{
this->declare_parameter<bool>("publish.path_en", true);
this->declare_parameter<bool>("publish.effect_map_en", false);
this->declare_parameter<bool>("publish.map_en", false);
this->declare_parameter<bool>("publish.scan_publish_en", true);
this->declare_parameter<bool>("publish.dense_publish_en", true);
this->declare_parameter<bool>("publish.scan_bodyframe_pub_en", true);
this->declare_parameter<int>("max_iteration", 4);
this->declare_parameter<string>("map_file_path", "");
this->declare_parameter<string>("common.lid_topic", "/livox/lidar");
this->declare_parameter<string>("common.imu_topic", "/livox/imu");
this->declare_parameter<bool>("common.time_sync_en", false);
this->declare_parameter<double>("common.time_offset_lidar_to_imu", 0.0);
this->declare_parameter<double>("filter_size_corner", 0.5);
this->declare_parameter<double>("filter_size_surf", 0.5);
this->declare_parameter<double>("filter_size_map", 0.5);
this->declare_parameter<double>("cube_side_length", 200.);
this->declare_parameter<float>("mapping.det_range", 300.);
this->declare_parameter<double>("mapping.fov_degree", 180.);
this->declare_parameter<double>("mapping.gyr_cov", 0.1);
this->declare_parameter<double>("mapping.acc_cov", 0.1);
this->declare_parameter<double>("mapping.b_gyr_cov", 0.0001);
this->declare_parameter<double>("mapping.b_acc_cov", 0.0001);
this->declare_parameter<double>("preprocess.blind", 0.01);
this->declare_parameter<int>("preprocess.lidar_type", AVIA);
this->declare_parameter<int>("preprocess.scan_line", 16);
this->declare_parameter<int>("preprocess.timestamp_unit", US);
this->declare_parameter<int>("preprocess.scan_rate", 10);
this->declare_parameter<int>("point_filter_num", 2);
this->declare_parameter<bool>("feature_extract_enable", false);
this->declare_parameter<bool>("runtime_pos_log_enable", false);
this->declare_parameter<bool>("mapping.extrinsic_est_en", true);
this->declare_parameter<bool>("pcd_save.pcd_save_en", false);
this->declare_parameter<int>("pcd_save.interval", -1);
this->declare_parameter<vector<double>>("mapping.extrinsic_T", vector<double>());
this->declare_parameter<vector<double>>("mapping.extrinsic_R", vector<double>());
this->get_parameter_or<bool>("publish.path_en", path_en, true);
this->get_parameter_or<bool>("publish.effect_map_en", effect_pub_en, false);
this->get_parameter_or<bool>("publish.map_en", map_pub_en, false);
this->get_parameter_or<bool>("publish.scan_publish_en", scan_pub_en, true);
this->get_parameter_or<bool>("publish.dense_publish_en", dense_pub_en, true);
this->get_parameter_or<bool>("publish.scan_bodyframe_pub_en", scan_body_pub_en, true);
this->get_parameter_or<int>("max_iteration", NUM_MAX_ITERATIONS, 4);
this->get_parameter_or<string>("map_file_path", map_file_path, "");
this->get_parameter_or<string>("common.lid_topic", lid_topic, "/livox/lidar");
this->get_parameter_or<string>("common.imu_topic", imu_topic,"/livox/imu");
this->get_parameter_or<bool>("common.time_sync_en", time_sync_en, false);
this->get_parameter_or<double>("common.time_offset_lidar_to_imu", time_diff_lidar_to_imu, 0.0);
this->get_parameter_or<double>("filter_size_corner",filter_size_corner_min,0.5);
this->get_parameter_or<double>("filter_size_surf",filter_size_surf_min,0.5);
this->get_parameter_or<double>("filter_size_map",filter_size_map_min,0.5);
this->get_parameter_or<double>("cube_side_length",cube_len,200.f);
this->get_parameter_or<float>("mapping.det_range",DET_RANGE,300.f);
this->get_parameter_or<double>("mapping.fov_degree",fov_deg,180.f);
this->get_parameter_or<double>("mapping.gyr_cov",gyr_cov,0.1);
this->get_parameter_or<double>("mapping.acc_cov",acc_cov,0.1);
this->get_parameter_or<double>("mapping.b_gyr_cov",b_gyr_cov,0.0001);
this->get_parameter_or<double>("mapping.b_acc_cov",b_acc_cov,0.0001);
this->get_parameter_or<double>("preprocess.blind", p_pre->blind, 0.01);
this->get_parameter_or<int>("preprocess.lidar_type", p_pre->lidar_type, AVIA);
this->get_parameter_or<int>("preprocess.scan_line", p_pre->N_SCANS, 16);
this->get_parameter_or<int>("preprocess.timestamp_unit", p_pre->time_unit, US);
this->get_parameter_or<int>("preprocess.scan_rate", p_pre->SCAN_RATE, 10);
this->get_parameter_or<int>("point_filter_num", p_pre->point_filter_num, 2);
this->get_parameter_or<bool>("feature_extract_enable", p_pre->feature_enabled, false);
this->get_parameter_or<bool>("runtime_pos_log_enable", runtime_pos_log, 0);
this->get_parameter_or<bool>("mapping.extrinsic_est_en", extrinsic_est_en, true);
this->get_parameter_or<bool>("pcd_save.pcd_save_en", pcd_save_en, false);
this->get_parameter_or<int>("pcd_save.interval", pcd_save_interval, -1);
this->get_parameter_or<vector<double>>("mapping.extrinsic_T", extrinT, vector<double>());
this->get_parameter_or<vector<double>>("mapping.extrinsic_R", extrinR, vector<double>());
RCLCPP_INFO(this->get_logger(), "p_pre->lidar_type %d", p_pre->lidar_type);
path.header.stamp = this->get_clock()->now();
path.header.frame_id ="camera_init";
// /*** variables definition ***/
// int effect_feat_num = 0, frame_num = 0;
// double deltaT, deltaR, aver_time_consu = 0, aver_time_icp = 0, aver_time_match = 0, aver_time_incre = 0, aver_time_solve = 0, aver_time_const_H_time = 0;
// bool flg_EKF_converged, EKF_stop_flg = 0;
FOV_DEG = (fov_deg + 10.0) > 179.9 ? 179.9 : (fov_deg + 10.0);
HALF_FOV_COS = cos((FOV_DEG) * 0.5 * PI_M / 180.0);
_featsArray.reset(new PointCloudXYZI());
memset(point_selected_surf, true, sizeof(point_selected_surf));
memset(res_last, -1000.0f, sizeof(res_last));
// 体素滤波器体素最小值
downSizeFilterSurf.setLeafSize(filter_size_surf_min, filter_size_surf_min, filter_size_surf_min);
downSizeFilterMap.setLeafSize(filter_size_map_min, filter_size_map_min, filter_size_map_min);
memset(point_selected_surf, true, sizeof(point_selected_surf));
memset(res_last, -1000.0f, sizeof(res_last));
// 设置 IMU 外参(相对雷达)与噪声模型
Lidar_T_wrt_IMU<<VEC_FROM_ARRAY(extrinT);
Lidar_R_wrt_IMU<<MAT_FROM_ARRAY(extrinR);
p_imu->set_extrinsic(Lidar_T_wrt_IMU, Lidar_R_wrt_IMU);
p_imu->set_gyr_cov(V3D(gyr_cov, gyr_cov, gyr_cov));
p_imu->set_acc_cov(V3D(acc_cov, acc_cov, acc_cov));
p_imu->set_gyr_bias_cov(V3D(b_gyr_cov, b_gyr_cov, b_gyr_cov));
p_imu->set_acc_bias_cov(V3D(b_acc_cov, b_acc_cov, b_acc_cov));
// 初始化滤波器/状态估计器
fill(epsi, epsi+23, 0.001);
kf.init_dyn_share(get_f, df_dx, df_dw, h_share_model, NUM_MAX_ITERATIONS, epsi);
/*** debug record ***/
// FILE *fp;
string pos_log_dir = root_dir + "/Log/pos_log.txt";
fp = fopen(pos_log_dir.c_str(),"w");
// ofstream fout_pre, fout_out, fout_dbg;
fout_pre.open(DEBUG_FILE_DIR("mat_pre.txt"),ios::out);
fout_out.open(DEBUG_FILE_DIR("mat_out.txt"),ios::out);
fout_dbg.open(DEBUG_FILE_DIR("dbg.txt"),ios::out);
if (fout_pre && fout_out)
cout << "~~~~"<<ROOT_DIR<<" file opened" << endl;
else
cout << "~~~~"<<ROOT_DIR<<" doesn't exist" << endl;
/*** ROS subscribe initialization ***/
sub_pcl_livox_ = this->create_subscription<livox_ros_driver2::msg::CustomMsg>(lid_topic, 20, livox_pcl_cbk);
sub_imu_ = this->create_subscription<sensor_msgs::msg::Imu>(imu_topic, 10, imu_cbk);
pubLaserCloudFull_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("/cloud_registered", 20);
pubLaserCloudFull_body_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("/cloud_registered_body", 20);
pubLaserCloudEffect_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("/cloud_effected", 20);
pubLaserCloudMap_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("/Laser_map", 20);
pubOdomAftMapped_ = this->create_publisher<nav_msgs::msg::Odometry>("/Odometry", 20);
pubPath_ = this->create_publisher<nav_msgs::msg::Path>("/path", 20);
tf_broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(*this);
//------------------------------------------------------------------------------------------------------
auto period_ms = std::chrono::milliseconds(static_cast<int64_t>(1000.0 / 100.0));
timer_ = rclcpp::create_timer(this, this->get_clock(), period_ms, std::bind(&LaserMappingNode::timer_callback, this));
auto map_period_ms = std::chrono::milliseconds(static_cast<int64_t>(1000.0));
map_pub_timer_ = rclcpp::create_timer(this, this->get_clock(), map_period_ms, std::bind(&LaserMappingNode::map_publish_callback, this));
map_save_srv_ = this->create_service<std_srvs::srv::Trigger>("map_save", std::bind(&LaserMappingNode::map_save_callback, this, std::placeholders::_1, std::placeholders::_2));
RCLCPP_INFO(this->get_logger(), "Node init finished.");
}
~LaserMappingNode()
{
fout_out.close();
fout_pre.close();
fclose(fp);
}
private:
void timer_callback()
{
// 缓冲区中提取一帧雷达 + 对应时间段的 IMU 数据
if(sync_packages(Measures))
{
// 第一次扫描,仅记录起始时间,不做处理。
// IMU 插值等都需要有前后帧
if (flg_first_scan)
{
first_lidar_time = Measures.lidar_beg_time;
p_imu->first_lidar_time = first_lidar_time;
flg_first_scan = false;
return;
}
double t0,t1,t2,t3,t4,t5,match_start, solve_start, svd_time;
match_time = 0;
kdtree_search_time = 0.0;
solve_time = 0;
solve_const_H_time = 0;
svd_time = 0;
t0 = omp_get_wtime();
// 对IMU数据进行预处理,其中包含了点云畸变处理 前向传播 反向传播
// feats_undistort是去畸变后的点云
p_imu->Process(Measures, kf, feats_undistort);
state_point = kf.get_x();
// IMU坐标系下的激光雷达位置转换到世界坐标系下的激光雷达位置
pos_lid = state_point.pos + state_point.rot * state_point.offset_T_L_I;
if (feats_undistort->empty() || (feats_undistort == NULL))
{
RCLCPP_WARN(this->get_logger(), "No point, skip this scan!\n");
return;
}
// 经过一定时间的初始化才启用 EKF 建图
flg_EKF_inited = (Measures.lidar_beg_time - first_lidar_time) < INIT_TIME ? \
false : true;
/*** Segment the map in lidar FOV ***/
lasermap_fov_segment();
/*** downsample the feature points in a scan ***/
downSizeFilterSurf.setInputCloud(feats_undistort);
downSizeFilterSurf.filter(*feats_down_body);
t1 = omp_get_wtime();
feats_down_size = feats_down_body->points.size();
/*** initialize the map kdtree ***/
if(ikdtree.Root_Node == nullptr)
{
RCLCPP_INFO(this->get_logger(), "Initialize the map kdtree");
if(feats_down_size > 5)
{
ikdtree.set_downsample_param(filter_size_map_min);
feats_down_world->resize(feats_down_size);
for(int i = 0; i < feats_down_size; i++)
{
pointBodyToWorld(&(feats_down_body->points[i]), &(feats_down_world->points[i]));
}
ikdtree.Build(feats_down_world->points);
}
return;
}
int featsFromMapNum = ikdtree.validnum();
kdtree_size_st = ikdtree.size();
// cout<<"[ mapping ]: In num: "<<feats_undistort->points.size()<<" downsamp "<<feats_down_size<<" Map num: "<<featsFromMapNum<<"effect num:"<<effct_feat_num<<endl;
/*** ICP and iterated Kalman filter update ***/
if (feats_down_size < 5)
{
RCLCPP_WARN(this->get_logger(), "No point, skip this scan!\n");
return;
}
normvec->resize(feats_down_size);
feats_down_world->resize(feats_down_size);
V3D ext_euler = SO3ToEuler(state_point.offset_R_L_I);
fout_pre<<setw(20)<<Measures.lidar_beg_time - first_lidar_time<<" "<<euler_cur.transpose()<<" "<< state_point.pos.transpose()<<" "<<ext_euler.transpose() << " "<<state_point.offset_T_L_I.transpose()<< " " << state_point.vel.transpose() \
<<" "<<state_point.bg.transpose()<<" "<<state_point.ba.transpose()<<" "<<state_point.grav<< endl;
if(0) // If you need to see map point, change to "if(1)"
{
PointVector ().swap(ikdtree.PCL_Storage);
ikdtree.flatten(ikdtree.Root_Node, ikdtree.PCL_Storage, NOT_RECORD);
featsFromMap->clear();
featsFromMap->points = ikdtree.PCL_Storage;
}