-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathlaser_mapping.cc
1147 lines (997 loc) · 47.2 KB
/
laser_mapping.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include <tf/transform_broadcaster.h>
#include <yaml-cpp/yaml.h>
#include <execution>
#include <fstream>
#include "laser_mapping.h"
#include "use-ikfom.hpp"
#include "utils.h"
namespace faster_lio {
bool LaserMapping::InitROS(ros::NodeHandle &nh) {
LoadParams(nh);
SubAndPubToROS(nh);
// localmap init (after LoadParams)
ivox_ = std::make_shared<IVoxType>(ivox_options_);
// esekf init
std::vector<double> epsi(23, 0.001);
if (is_extract_large_planes_) {
kf_.init_dyn_share(
get_f, df_dx, df_dw,
[this](state_ikfom &s, esekfom::dyn_share_datastruct<double> &ekfom_data) { ObsModelOurs(s, ekfom_data); },
options::NUM_MAX_ITERATIONS, epsi.data());
} else {
kf_.init_dyn_share(
get_f, df_dx, df_dw,
[this](state_ikfom &s, esekfom::dyn_share_datastruct<double> &ekfom_data) { ObsModel(s, ekfom_data); },
options::NUM_MAX_ITERATIONS, epsi.data());
}
plane_tracker_.SetIncrementalFitting(is_incremental_fitting_);
plane_tracker_.SetPlaneLeastInliers(plane_least_inliers_);
return true;
}
bool LaserMapping::InitWithoutROS(const std::string &config_yaml) {
LOG(INFO) << "init laser mapping from " << config_yaml;
if (!LoadParamsFromYAML(config_yaml)) {
return false;
}
// localmap init (after LoadParams)
ivox_ = std::make_shared<IVoxType>(ivox_options_);
// esekf init
std::vector<double> epsi(23, 0.001);
if (is_extract_large_planes_) {
kf_.init_dyn_share(
get_f, df_dx, df_dw,
[this](state_ikfom &s, esekfom::dyn_share_datastruct<double> &ekfom_data) { ObsModelOurs(s, ekfom_data); },
options::NUM_MAX_ITERATIONS, epsi.data());
} else {
kf_.init_dyn_share(
get_f, df_dx, df_dw,
[this](state_ikfom &s, esekfom::dyn_share_datastruct<double> &ekfom_data) { ObsModel(s, ekfom_data); },
options::NUM_MAX_ITERATIONS, epsi.data());
}
if (std::is_same<IVoxType, IVox<3, IVoxNodeType::PHC, pcl::PointXYZI>>()) {
LOG(INFO) << "using phc ivox";
} else if (std::is_same<IVoxType, IVox<3, IVoxNodeType::DEFAULT, pcl::PointXYZI>>()) {
LOG(INFO) << "using default ivox";
}
plane_tracker_.SetIncrementalFitting(is_incremental_fitting_);
plane_tracker_.SetPlaneLeastInliers(plane_least_inliers_);
return true;
}
bool LaserMapping::LoadParams(ros::NodeHandle &nh) {
// get params from param server
int lidar_type, ivox_nearby_type;
double gyr_cov, acc_cov, b_gyr_cov, b_acc_cov;
double filter_size_surf_min;
common::V3D lidar_T_wrt_IMU;
common::M3D lidar_R_wrt_IMU;
nh.param<bool>("path_save_en", path_save_en_, true);
nh.param<bool>("publish/path_publish_en", path_pub_en_, true);
nh.param<bool>("publish/scan_publish_en", scan_pub_en_, true);
nh.param<bool>("publish/dense_publish_en", dense_pub_en_, false);
nh.param<bool>("publish/scan_bodyframe_pub_en", scan_body_pub_en_, true);
nh.param<bool>("publish/scan_effect_pub_en", scan_effect_pub_en_, false);
nh.param<bool>("is_extract_large_planes", is_extract_large_planes_, false);
nh.param<int>("plane_least_inliers", plane_least_inliers_, -1);
nh.param<float>("point_to_plane_thresh", point_to_plane_thresh_, 0.2f);
nh.param<bool>("is_incremental_fitting", is_incremental_fitting_, false);
nh.param<int>("max_iteration", options::NUM_MAX_ITERATIONS, 4);
nh.param<float>("esti_plane_threshold", options::ESTI_PLANE_THRESHOLD, 0.1);
nh.param<std::string>("map_file_path", map_file_path_, "");
nh.param<bool>("common/time_sync_en", time_sync_en_, false);
nh.param<double>("filter_size_surf", filter_size_surf_min, 0.5);
nh.param<double>("filter_size_map", filter_size_map_min_, 0.0);
nh.param<double>("cube_side_length", cube_len_, 200);
nh.param<float>("mapping/det_range", det_range_, 300.f);
nh.param<double>("mapping/gyr_cov", gyr_cov, 0.1);
nh.param<double>("mapping/acc_cov", acc_cov, 0.1);
nh.param<double>("mapping/b_gyr_cov", b_gyr_cov, 0.0001);
nh.param<double>("mapping/b_acc_cov", b_acc_cov, 0.0001);
nh.param<double>("preprocess/blind", preprocess_->Blind(), 0.01);
nh.param<float>("preprocess/time_scale", preprocess_->TimeScale(), 1e-3);
nh.param<int>("preprocess/lidar_type", lidar_type, 1);
nh.param<int>("preprocess/scan_line", preprocess_->NumScans(), 16);
nh.param<int>("point_filter_num", preprocess_->PointFilterNum(), 2);
nh.param<bool>("feature_extract_enable", preprocess_->FeatureEnabled(), false);
nh.param<bool>("runtime_pos_log_enable", runtime_pos_log_, true);
nh.param<bool>("mapping/extrinsic_est_en", extrinsic_est_en_, true);
nh.param<bool>("pcd_save/pcd_save_en", pcd_save_en_, false);
nh.param<int>("pcd_save/interval", pcd_save_interval_, -1);
nh.param<std::vector<double>>("mapping/extrinsic_T", extrinT_, std::vector<double>());
nh.param<std::vector<double>>("mapping/extrinsic_R", extrinR_, std::vector<double>());
nh.param<float>("ivox_grid_resolution", ivox_options_.resolution_, 0.2);
nh.param<int>("ivox_nearby_type", ivox_nearby_type, 18);
LOG(INFO) << "lidar_type " << lidar_type;
if (lidar_type == 1) {
preprocess_->SetLidarType(LidarType::AVIA);
LOG(INFO) << "Using AVIA Lidar";
} else if (lidar_type == 2) {
preprocess_->SetLidarType(LidarType::VELO32);
LOG(INFO) << "Using Velodyne 32 Lidar";
} else if (lidar_type == 3) {
preprocess_->SetLidarType(LidarType::OUST64);
LOG(INFO) << "Using OUST 64 Lidar";
} else {
LOG(WARNING) << "unknown lidar_type";
return false;
}
if (ivox_nearby_type == 0) {
ivox_options_.nearby_type_ = IVoxType::NearbyType::CENTER;
} else if (ivox_nearby_type == 6) {
ivox_options_.nearby_type_ = IVoxType::NearbyType::NEARBY6;
} else if (ivox_nearby_type == 18) {
ivox_options_.nearby_type_ = IVoxType::NearbyType::NEARBY18;
} else if (ivox_nearby_type == 26) {
ivox_options_.nearby_type_ = IVoxType::NearbyType::NEARBY26;
} else {
LOG(WARNING) << "unknown ivox_nearby_type, use NEARBY18";
ivox_options_.nearby_type_ = IVoxType::NearbyType::NEARBY18;
}
path_.header.stamp = ros::Time::now();
path_.header.frame_id = "camera_init";
voxel_scan_.setLeafSize(filter_size_surf_min, filter_size_surf_min, filter_size_surf_min);
lidar_T_wrt_IMU = common::VecFromArray<double>(extrinT_);
lidar_R_wrt_IMU = common::MatFromArray<double>(extrinR_);
p_imu_->SetExtrinsic(lidar_T_wrt_IMU, lidar_R_wrt_IMU);
p_imu_->SetGyrCov(common::V3D(gyr_cov, gyr_cov, gyr_cov));
p_imu_->SetAccCov(common::V3D(acc_cov, acc_cov, acc_cov));
p_imu_->SetGyrBiasCov(common::V3D(b_gyr_cov, b_gyr_cov, b_gyr_cov));
p_imu_->SetAccBiasCov(common::V3D(b_acc_cov, b_acc_cov, b_acc_cov));
return true;
}
bool LaserMapping::LoadParamsFromYAML(const std::string &yaml_file) {
// get params from yaml
int lidar_type, ivox_nearby_type;
double gyr_cov, acc_cov, b_gyr_cov, b_acc_cov;
double filter_size_surf_min;
common::V3D lidar_T_wrt_IMU;
common::M3D lidar_R_wrt_IMU;
auto yaml = YAML::LoadFile(yaml_file);
try {
path_pub_en_ = yaml["publish"]["path_publish_en"].as<bool>();
scan_pub_en_ = yaml["publish"]["scan_publish_en"].as<bool>();
dense_pub_en_ = yaml["publish"]["dense_publish_en"].as<bool>();
scan_body_pub_en_ = yaml["publish"]["scan_bodyframe_pub_en"].as<bool>();
scan_effect_pub_en_ = yaml["publish"]["scan_effect_pub_en"].as<bool>();
path_save_en_ = yaml["path_save_en"].as<bool>();
is_extract_large_planes_ = yaml["is_extract_large_planes"].as<bool>();
plane_least_inliers_ = yaml["plane_least_inliers"].as<int>();
point_to_plane_thresh_ = yaml["point_to_plane_thresh"].as<float>();
is_incremental_fitting_ = yaml["is_incremental_fitting"].as<bool>();
options::NUM_MAX_ITERATIONS = yaml["max_iteration"].as<int>();
options::ESTI_PLANE_THRESHOLD = yaml["esti_plane_threshold"].as<float>();
time_sync_en_ = yaml["common"]["time_sync_en"].as<bool>();
filter_size_surf_min = yaml["filter_size_surf"].as<float>();
filter_size_map_min_ = yaml["filter_size_map"].as<float>();
cube_len_ = yaml["cube_side_length"].as<int>();
det_range_ = yaml["mapping"]["det_range"].as<float>();
gyr_cov = yaml["mapping"]["gyr_cov"].as<float>();
acc_cov = yaml["mapping"]["acc_cov"].as<float>();
b_gyr_cov = yaml["mapping"]["b_gyr_cov"].as<float>();
b_acc_cov = yaml["mapping"]["b_acc_cov"].as<float>();
preprocess_->Blind() = yaml["preprocess"]["blind"].as<double>();
preprocess_->TimeScale() = yaml["preprocess"]["time_scale"].as<double>();
lidar_type = yaml["preprocess"]["lidar_type"].as<int>();
preprocess_->NumScans() = yaml["preprocess"]["scan_line"].as<int>();
preprocess_->PointFilterNum() = yaml["point_filter_num"].as<int>();
preprocess_->FeatureEnabled() = yaml["feature_extract_enable"].as<bool>();
extrinsic_est_en_ = yaml["mapping"]["extrinsic_est_en"].as<bool>();
pcd_save_en_ = yaml["pcd_save"]["pcd_save_en"].as<bool>();
pcd_save_interval_ = yaml["pcd_save"]["interval"].as<int>();
extrinT_ = yaml["mapping"]["extrinsic_T"].as<std::vector<double>>();
extrinR_ = yaml["mapping"]["extrinsic_R"].as<std::vector<double>>();
ivox_options_.resolution_ = yaml["ivox_grid_resolution"].as<float>();
ivox_nearby_type = yaml["ivox_nearby_type"].as<int>();
} catch (...) {
LOG(ERROR) << "bad conversion";
return false;
}
LOG(INFO) << "lidar_type " << lidar_type;
if (lidar_type == 1) {
preprocess_->SetLidarType(LidarType::AVIA);
LOG(INFO) << "Using AVIA Lidar";
} else if (lidar_type == 2) {
preprocess_->SetLidarType(LidarType::VELO32);
LOG(INFO) << "Using Velodyne 32 Lidar";
} else if (lidar_type == 3) {
preprocess_->SetLidarType(LidarType::OUST64);
LOG(INFO) << "Using OUST 64 Lidar";
} else {
LOG(WARNING) << "unknown lidar_type";
return false;
}
if (ivox_nearby_type == 0) {
ivox_options_.nearby_type_ = IVoxType::NearbyType::CENTER;
} else if (ivox_nearby_type == 6) {
ivox_options_.nearby_type_ = IVoxType::NearbyType::NEARBY6;
} else if (ivox_nearby_type == 18) {
ivox_options_.nearby_type_ = IVoxType::NearbyType::NEARBY18;
} else if (ivox_nearby_type == 26) {
ivox_options_.nearby_type_ = IVoxType::NearbyType::NEARBY26;
} else {
LOG(WARNING) << "unknown ivox_nearby_type, use NEARBY18";
ivox_options_.nearby_type_ = IVoxType::NearbyType::NEARBY18;
}
voxel_scan_.setLeafSize(filter_size_surf_min, filter_size_surf_min, filter_size_surf_min);
lidar_T_wrt_IMU = common::VecFromArray<double>(extrinT_);
lidar_R_wrt_IMU = common::MatFromArray<double>(extrinR_);
p_imu_->SetExtrinsic(lidar_T_wrt_IMU, lidar_R_wrt_IMU);
p_imu_->SetGyrCov(common::V3D(gyr_cov, gyr_cov, gyr_cov));
p_imu_->SetAccCov(common::V3D(acc_cov, acc_cov, acc_cov));
p_imu_->SetGyrBiasCov(common::V3D(b_gyr_cov, b_gyr_cov, b_gyr_cov));
p_imu_->SetAccBiasCov(common::V3D(b_acc_cov, b_acc_cov, b_acc_cov));
run_in_offline_ = true;
return true;
}
void LaserMapping::SubAndPubToROS(ros::NodeHandle &nh) {
// ROS subscribe initialization
std::string lidar_topic, imu_topic;
nh.param<std::string>("common/lid_topic", lidar_topic, "/livox/lidar");
nh.param<std::string>("common/imu_topic", imu_topic, "/livox/imu");
if (preprocess_->GetLidarType() == LidarType::AVIA) {
sub_pcl_ = nh.subscribe<livox_ros_driver::CustomMsg>(
lidar_topic, 200000, [this](const livox_ros_driver::CustomMsg::ConstPtr &msg) { LivoxPCLCallBack(msg); });
} else {
sub_pcl_ = nh.subscribe<sensor_msgs::PointCloud2>(
lidar_topic, 200000, [this](const sensor_msgs::PointCloud2::ConstPtr &msg) { StandardPCLCallBack(msg); });
}
sub_imu_ = nh.subscribe<sensor_msgs::Imu>(imu_topic, 200000,
[this](const sensor_msgs::Imu::ConstPtr &msg) { IMUCallBack(msg); });
// ROS publisher init
path_.header.stamp = ros::Time::now();
path_.header.frame_id = "camera_init";
pub_laser_cloud_world_ = nh.advertise<sensor_msgs::PointCloud2>("/cloud_registered", 100000);
pub_laser_cloud_body_ = nh.advertise<sensor_msgs::PointCloud2>("/cloud_registered_body", 100000);
pub_laser_cloud_effect_world_ = nh.advertise<sensor_msgs::PointCloud2>("/cloud_registered_effect_world", 100000);
pub_odom_aft_mapped_ = nh.advertise<nav_msgs::Odometry>("/Odometry", 100000);
pub_path_ = nh.advertise<nav_msgs::Path>("/path", 100000);
}
LaserMapping::LaserMapping() {
preprocess_.reset(new PointCloudPreprocess());
p_imu_.reset(new ImuProcess());
}
void LaserMapping::Run() {
if (!SyncPackages()) {
return;
}
/// IMU process, kf prediction, undistortion
p_imu_->Process(measures_, kf_, scan_undistort_);
// FIXME
if (scan_undistort_->empty() || (scan_undistort_ == nullptr)) {
LOG(WARNING) << "No point, skip this scan!";
return;
}
/// the first scan
if (flg_first_scan_) {
ivox_->AddPoints(scan_undistort_->points);
first_lidar_time_ = measures_.lidar_bag_time_;
flg_first_scan_ = false;
return;
}
flg_EKF_inited_ = (measures_.lidar_bag_time_ - first_lidar_time_) >= options::INIT_TIME;
/// downsample
Timer::Evaluate(
[&, this]() {
voxel_scan_.setInputCloud(scan_undistort_);
voxel_scan_.filter(*scan_down_body_);
},
"Downsample PointCloud");
int cur_pts = scan_down_body_->size();
if (cur_pts < 5) {
LOG(WARNING) << "Too few points, skip this scan!" << scan_undistort_->size() << ", " << scan_down_body_->size();
return;
}
if (is_extract_large_planes_) {
// D_RECORD_TIME_START;
if (is_incremental_fitting_) {
state_ikfom pose_pre_int = kf_.get_x();
Eigen::Quaternionf q_wl = (pose_pre_int.rot * pose_pre_int.offset_R_L_I).cast<float>();
Eigen::Vector3f t_wl = (pose_pre_int.rot * pose_pre_int.offset_T_L_I +
pose_pre_int.pos).cast<float>();
plane_tracker_.ExtractLargePlanes(scan_down_body_, &t_wl, &q_wl);
} else {
plane_tracker_.ExtractLargePlanes(scan_down_body_, (Eigen::Matrix4f *) nullptr);
}
scan_down_body_plane_ = plane_tracker_.CurrCloudPlane();
scan_down_body_other_ = plane_tracker_.CurrCloudOther();
// D_RECORD_TIME_END("ExtractLargePlanes");
}
if (is_extract_large_planes_) {
int n_other = (int) scan_down_body_other_->size();
scan_down_world_other_->resize(n_other);
nearest_points_.resize(n_other);
} else {
// scan_down_world_在MapIncremental()里面写
scan_down_world_->resize(cur_pts);
nearest_points_.resize(cur_pts);
}
residuals_.resize(cur_pts, 0);
point_selected_surf_.resize(cur_pts, false);
plane_coef_.resize(cur_pts, common::V4F::Zero());
// ICP and iterated Kalman filter update
Timer::Evaluate(
[&, this]() {
// iterated state estimation
double solve_H_time = 0;
// update the observation model, will call nn and point-to-plane residual computation
kf_.update_iterated_dyn_share_modified(options::LASER_POINT_COV, solve_H_time);
// save the state
state_point_ = kf_.get_x();
euler_cur_ = SO3ToEuler(state_point_.rot);
// t_wl = t_wb + t_w_bl
// = t_wb + q_wb * t_bl
pos_lidar_ = state_point_.pos + state_point_.rot * state_point_.offset_T_L_I;
},
"IEKF Solve and Update");
// update local map
if (is_extract_large_planes_) {
Timer::Evaluate([&, this]() { MapIncrementalOurs(); }, " Incremental Mapping Ours");
} else {
Timer::Evaluate([&, this]() { MapIncremental(); }, " Incremental Mapping");
}
// publish or save map pcd
if (run_in_offline_) {
if (pcd_save_en_) {
PublishFrameWorld();
}
if (path_save_en_) {
PublishPath(pub_path_);
}
} else {
if (pub_odom_aft_mapped_) {
PublishOdometry(pub_odom_aft_mapped_);
}
if (path_pub_en_ || path_save_en_) {
PublishPath(pub_path_);
}
if (scan_pub_en_ || pcd_save_en_) {
// 把lidar系下的点云(scan_undistort_) 转到imu系下面,再用state_point_.rot从imu转到world
PublishFrameWorld();
}
if (scan_pub_en_ && scan_body_pub_en_) {
// 把lidar系下的点云(scan_undistort_) 转到imu系下面
PublishFrameBody(pub_laser_cloud_body_);
}
if (scan_pub_en_ && scan_effect_pub_en_) {
PublishFrameEffectWorld(pub_laser_cloud_effect_world_);
}
}
// q_wb * q_bl
Eigen::Quaternionf q_wl = (state_point_.rot * state_point_.offset_R_L_I).cast<float>();
Eigen::Vector3f t_wl = (state_point_.rot * state_point_.offset_T_L_I +
state_point_.pos).cast<float>();
plane_tracker_.SetCurrTransWl(t_wl, q_wl);
// Debug variables
frame_num_++;
}
void LaserMapping::StandardPCLCallBack(const sensor_msgs::PointCloud2::ConstPtr &msg) {
mtx_buffer_.lock();
Timer::Evaluate(
[&, this]() {
scan_count_++;
if (msg->header.stamp.toSec() < last_timestamp_lidar_) {
LOG(ERROR) << "lidar loop back, clear buffer";
lidar_buffer_.clear();
}
PointCloudType::Ptr ptr(new PointCloudType());
preprocess_->Process(msg, ptr);
lidar_buffer_.push_back(ptr);
time_buffer_.push_back(msg->header.stamp.toSec());
last_timestamp_lidar_ = msg->header.stamp.toSec();
},
"Preprocess (Standard)");
mtx_buffer_.unlock();
}
void LaserMapping::LivoxPCLCallBack(const livox_ros_driver::CustomMsg::ConstPtr &msg) {
mtx_buffer_.lock();
Timer::Evaluate(
[&, this]() {
scan_count_++;
if (msg->header.stamp.toSec() < last_timestamp_lidar_) {
LOG(WARNING) << "lidar loop back, clear buffer";
lidar_buffer_.clear();
}
last_timestamp_lidar_ = msg->header.stamp.toSec();
if (!time_sync_en_ && abs(last_timestamp_imu_ - last_timestamp_lidar_) > 10.0
&& !imu_buffer_.empty() && !lidar_buffer_.empty()) {
LOG(INFO) << "IMU and LiDAR not Synced, IMU time: " << last_timestamp_imu_
<< ", lidar header time: " << 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_;
LOG(INFO) << "Self sync IMU and LiDAR, time diff is " << timediff_lidar_wrt_imu_;
}
PointCloudType::Ptr ptr(new PointCloudType());
preprocess_->Process(msg, ptr);
lidar_buffer_.emplace_back(ptr);
time_buffer_.emplace_back(last_timestamp_lidar_);
},
"Preprocess (Livox)");
mtx_buffer_.unlock();
}
void LaserMapping::IMUCallBack(const sensor_msgs::Imu::ConstPtr &msg_in) {
publish_count_++;
sensor_msgs::Imu::Ptr msg(new sensor_msgs::Imu(*msg_in));
if (abs(timediff_lidar_wrt_imu_) > 0.1 && time_sync_en_) {
msg->header.stamp = ros::Time().fromSec(timediff_lidar_wrt_imu_ + msg_in->header.stamp.toSec());
}
double timestamp = msg->header.stamp.toSec();
mtx_buffer_.lock();
if (timestamp < last_timestamp_imu_) {
LOG(WARNING) << "imu loop back, clear buffer";
imu_buffer_.clear();
}
last_timestamp_imu_ = timestamp;
imu_buffer_.emplace_back(msg);
mtx_buffer_.unlock();
}
bool LaserMapping::SyncPackages() {
if (lidar_buffer_.empty() || imu_buffer_.empty()) {
return false;
}
/*** push a lidar scan ***/
if (!lidar_pushed_) {
measures_.lidar_ = lidar_buffer_.front();
measures_.lidar_bag_time_ = time_buffer_.front();
if (measures_.lidar_->points.size() <= 1) {
LOG(WARNING) << "Too few input point cloud!";
lidar_end_time_ = measures_.lidar_bag_time_ + lidar_mean_scantime_;
} else if (measures_.lidar_->points.back().curvature / double(1000) < 0.5 * lidar_mean_scantime_) {
lidar_end_time_ = measures_.lidar_bag_time_ + lidar_mean_scantime_;
} else {
scan_num_++;
lidar_end_time_ = measures_.lidar_bag_time_ + measures_.lidar_->points.back().curvature / double(1000);
lidar_mean_scantime_ +=
(measures_.lidar_->points.back().curvature / double(1000) - lidar_mean_scantime_) / scan_num_;
}
measures_.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 = imu_buffer_.front()->header.stamp.toSec();
measures_.imu_.clear();
while ((!imu_buffer_.empty()) && (imu_time < lidar_end_time_)) {
imu_time = imu_buffer_.front()->header.stamp.toSec();
if (imu_time > lidar_end_time_) break;
measures_.imu_.push_back(imu_buffer_.front());
imu_buffer_.pop_front();
}
lidar_buffer_.pop_front();
time_buffer_.pop_front();
lidar_pushed_ = false;
return true;
}
void LaserMapping::PrintState(const state_ikfom &s) {
LOG(INFO) << "state r: " << s.rot.coeffs().transpose() << ", t: " << s.pos.transpose()
<< ", off r: " << s.offset_R_L_I.coeffs().transpose() << ", t: " << s.offset_T_L_I.transpose();
}
void LaserMapping::MapIncrementalOurs() {
PointVector points_to_add;
PointVector point_no_need_downsample;
int cur_pts = (int) scan_down_body_other_->size(); // only non-skeleton points
points_to_add.reserve(cur_pts);
point_no_need_downsample.reserve(cur_pts);
std::vector<size_t> index(cur_pts);
for (size_t i = 0; i < cur_pts; ++i) {
index[i] = i;
}
std::for_each(std::execution::unseq, index.begin(), index.end(), [&](const size_t &i) {
/* transform to world frame */
PointBodyToWorld(&(scan_down_body_other_->points[i]),
&(scan_down_world_other_->points[i]));
/* decide if need add to map */
PointType &point_world = scan_down_world_other_->points[i];
if (!nearest_points_[i].empty() && flg_EKF_inited_) {
const PointVector &points_near = nearest_points_[i];
Eigen::Vector3f center =
((point_world.getVector3fMap() / filter_size_map_min_).array().floor() + 0.5) * filter_size_map_min_;
Eigen::Vector3f dis_2_center = points_near[0].getVector3fMap() - center;
if (fabs(dis_2_center.x()) > 0.5 * filter_size_map_min_ &&
fabs(dis_2_center.y()) > 0.5 * filter_size_map_min_ &&
fabs(dis_2_center.z()) > 0.5 * filter_size_map_min_) {
point_no_need_downsample.emplace_back(point_world);
return;
}
bool need_add = true;
float dist = common::calc_dist(point_world.getVector3fMap(), center);
if (points_near.size() >= options::NUM_MATCH_POINTS) {
for (int readd_i = 0; readd_i < options::NUM_MATCH_POINTS; readd_i++) {
if (common::calc_dist(points_near[readd_i].getVector3fMap(), center) < dist + 1e-6) {
need_add = false;
break;
}
}
}
if (need_add) {
points_to_add.emplace_back(point_world);
}
} else {
points_to_add.emplace_back(point_world);
}
});
Timer::Evaluate([&, this]() {
ivox_->AddPoints(points_to_add);
ivox_->AddPoints(point_no_need_downsample);
}, " IVox Add Points");
}
void LaserMapping::MapIncremental() {
PointVector points_to_add;
PointVector point_no_need_downsample;
int cur_pts = scan_down_body_->size();
points_to_add.reserve(cur_pts);
point_no_need_downsample.reserve(cur_pts);
std::vector<size_t> index(cur_pts);
for (size_t i = 0; i < cur_pts; ++i) {
index[i] = i;
}
std::for_each(std::execution::unseq, index.begin(), index.end(), [&](const size_t &i) {
/* transform to world frame */
PointBodyToWorld(&(scan_down_body_->points[i]), &(scan_down_world_->points[i]));
/* decide if need add to map */
PointType &point_world = scan_down_world_->points[i];
if (!nearest_points_[i].empty() && flg_EKF_inited_) {
const PointVector &points_near = nearest_points_[i];
Eigen::Vector3f center =
((point_world.getVector3fMap() / filter_size_map_min_).array().floor() + 0.5) * filter_size_map_min_;
Eigen::Vector3f dis_2_center = points_near[0].getVector3fMap() - center;
if (fabs(dis_2_center.x()) > 0.5 * filter_size_map_min_ &&
fabs(dis_2_center.y()) > 0.5 * filter_size_map_min_ &&
fabs(dis_2_center.z()) > 0.5 * filter_size_map_min_) {
point_no_need_downsample.emplace_back(point_world);
return;
}
bool need_add = true;
float dist = common::calc_dist(point_world.getVector3fMap(), center);
if (points_near.size() >= options::NUM_MATCH_POINTS) {
for (int readd_i = 0; readd_i < options::NUM_MATCH_POINTS; readd_i++) {
if (common::calc_dist(points_near[readd_i].getVector3fMap(), center) < dist + 1e-6) {
need_add = false;
break;
}
}
}
if (need_add) {
points_to_add.emplace_back(point_world);
}
} else {
points_to_add.emplace_back(point_world);
}
});
Timer::Evaluate(
[&, this]() {
ivox_->AddPoints(points_to_add);
ivox_->AddPoints(point_no_need_downsample);
},
" IVox Add Points");
}
void LaserMapping::ObsModelOurs(state_ikfom &s, esekfom::dyn_share_datastruct<double> &ekfom_data) {
int plane_n_pts = (int) scan_down_body_plane_->size();
int other_n_pts = (int) scan_down_body_other_->size();
int total_n_pts = plane_n_pts + other_n_pts;
std::vector<size_t> index_all(total_n_pts);
for (size_t i = 0; i < total_n_pts; ++i) {
index_all[i] = i;
}
std::vector<size_t> index_plane(index_all.begin(), index_all.begin() + plane_n_pts);
std::vector<size_t> index_other(index_all.begin(), index_all.begin() + other_n_pts);
Timer::Evaluate([&, this]() {
const int n_planes = plane_tracker_.NumPlanes();
auto &last_planes = plane_tracker_.LastPlanes();
// R_wb * R_bl
auto R_wl = (s.rot * s.offset_R_L_I).cast<float>();
auto t_wl = (s.rot * s.offset_T_L_I + s.pos).cast<float>();
std::for_each(std::execution::par_unseq,
index_plane.begin(), index_plane.end(), [&](const size_t &i) {
PointType &point_body = scan_down_body_plane_->points[i];
PointType point_world;
/* transform to world frame */
common::V3F p_body = point_body.getVector3fMap();
point_world.getVector3fMap() = R_wl * p_body + t_wl;
point_world.intensity = point_body.intensity;
if (ekfom_data.converge) {
float min_dist = std::numeric_limits<float>::max();
for (auto &candidate_plane : last_planes) {
float dist = Point2PlaneDist(point_world, candidate_plane.coef);
if (dist < point_to_plane_thresh_ && dist < min_dist) {
min_dist = dist;
point_selected_surf_[i] = true;
plane_coef_[i] = candidate_plane.coef;
}
}
}
if (point_selected_surf_[i]) {
auto temp = point_world.getVector4fMap();
temp[3] = 1.0;
float pd2 = plane_coef_[i].dot(temp);
bool valid_corr = p_body.norm() > 81 * pd2 * pd2;
if (valid_corr) {
residuals_[i] = pd2;
}
}
});
std::for_each(std::execution::par_unseq,
index_other.begin(), index_other.end(), [&](const size_t &i) {
PointType &point_body = scan_down_body_other_->points[i];
PointType point_world;
/* transform to world frame */
common::V3F p_body = point_body.getVector3fMap();
point_world.getVector3fMap() = R_wl * p_body + t_wl;
point_world.intensity = point_body.intensity;
int idx = i + plane_n_pts;
auto &points_near = nearest_points_[i];
if (ekfom_data.converge) {
/** Find the closest surfaces in the map **/
ivox_->GetClosestPoint(point_world, points_near, options::NUM_MATCH_POINTS);
point_selected_surf_[idx] = points_near.size() >= options::MIN_NUM_MATCH_POINTS;
if (point_selected_surf_[idx]) {
point_selected_surf_[idx] =
common::esti_plane(plane_coef_[idx], points_near, options::ESTI_PLANE_THRESHOLD);
}
}
if (point_selected_surf_[idx]) {
auto temp = point_world.getVector4fMap();
temp[3] = 1.0;
float pd2 = plane_coef_[idx].dot(temp);
bool valid_corr = p_body.norm() > 81 * pd2 * pd2;
if (valid_corr) {
residuals_[idx] = pd2;
// } else {
// point_selected_surf_[idx] = false;
}
}
});
}, " ObsModelOurs (Lidar Match)");
effect_feat_num_ = 0;
corr_pts_.resize(total_n_pts);
corr_norm_.resize(total_n_pts);
for (int i = 0; i < total_n_pts; i++) {
if (point_selected_surf_[i]) {
corr_norm_[effect_feat_num_] = plane_coef_[i];
if (i < plane_n_pts) {
corr_pts_[effect_feat_num_] = scan_down_body_plane_->points[i].getVector4fMap();
} else {
corr_pts_[effect_feat_num_] =
scan_down_body_other_->points[i - plane_n_pts].getVector4fMap();
}
corr_pts_[effect_feat_num_][3] = residuals_[i];
effect_feat_num_++;
}
}
corr_pts_.resize(effect_feat_num_);
corr_norm_.resize(effect_feat_num_);
if (effect_feat_num_ < 1) {
ekfom_data.valid = false;
LOG(WARNING) << "No Effective Points!";
return;
}
Timer::Evaluate(
[&, this]() {
/*** Computation of Measurement Jacobian matrix H and measurements vector ***/
ekfom_data.h_x = Eigen::MatrixXd::Zero(effect_feat_num_, 12); // 23
ekfom_data.h.resize(effect_feat_num_);
index_all.resize(effect_feat_num_);
const common::M3F off_R = s.offset_R_L_I.toRotationMatrix().cast<float>();
const common::V3F off_t = s.offset_T_L_I.cast<float>();
const common::M3F Rt = s.rot.toRotationMatrix().transpose().cast<float>();
std::for_each(std::execution::par_unseq,
index_all.begin(), index_all.end(), [&](const size_t &i) {
common::V3F point_this_be = corr_pts_[i].head<3>();
common::M3F point_be_crossmat = SKEW_SYM_MATRIX(point_this_be);
common::V3F point_this = off_R * point_this_be + off_t;
common::M3F point_crossmat = SKEW_SYM_MATRIX(point_this);
/*** get the normal vector of closest surface/corner ***/
common::V3F norm_vec = corr_norm_[i].head<3>();
/*** calculate the Measurement Jacobian matrix H ***/
common::V3F C(Rt * norm_vec);
common::V3F A(point_crossmat * C);
if (extrinsic_est_en_) {
common::V3F B(point_be_crossmat * off_R.transpose() * C);
ekfom_data.h_x.block<1, 12>(i, 0) << norm_vec[0], norm_vec[1], norm_vec[2], A[0], A[1], A[2], B[0],
B[1], B[2], C[0], C[1], C[2];
} else {
ekfom_data.h_x.block<1, 12>(i, 0) << norm_vec[0], norm_vec[1], norm_vec[2], A[0], A[1], A[2], 0.0,
0.0, 0.0, 0.0, 0.0, 0.0;
}
/*** Measurement: distance to the closest surface/corner ***/
ekfom_data.h(i) = -corr_pts_[i][3];
});
}, " ObsModelOurs (IEKF Build Jacobian)");
}
/**
* Lidar point cloud registration
* will be called by the eskf custom observation model
* compute point-to-plane residual here
* @param s kf state
* @param ekfom_data H matrix
*/
void LaserMapping::ObsModel(state_ikfom &s, esekfom::dyn_share_datastruct<double> &ekfom_data) {
int cnt_pts = scan_down_body_->size();
std::vector<size_t> index(cnt_pts);
for (size_t i = 0; i < index.size(); ++i) {
index[i] = i;
}
Timer::Evaluate(
[&, this]() {
// R_wb * R_bl
auto R_wl = (s.rot * s.offset_R_L_I).cast<float>();
auto t_wl = (s.rot * s.offset_T_L_I + s.pos).cast<float>();
/** closest surface search and residual computation **/
std::for_each(std::execution::par_unseq, index.begin(), index.end(), [&](const size_t &i) {
PointType &point_body = scan_down_body_->points[i];
PointType &point_world = scan_down_world_->points[i];
/* transform to world frame */
common::V3F p_body = point_body.getVector3fMap();
point_world.getVector3fMap() = R_wl * p_body + t_wl;
point_world.intensity = point_body.intensity;
auto &points_near = nearest_points_[i];
if (ekfom_data.converge) {
/** Find the closest surfaces in the map **/
ivox_->GetClosestPoint(point_world, points_near, options::NUM_MATCH_POINTS);
point_selected_surf_[i] = points_near.size() >= options::MIN_NUM_MATCH_POINTS;
if (point_selected_surf_[i]) {
point_selected_surf_[i] =
common::esti_plane(plane_coef_[i], points_near, options::ESTI_PLANE_THRESHOLD);
}
}
if (point_selected_surf_[i]) {
auto temp = point_world.getVector4fMap();
temp[3] = 1.0;
float pd2 = plane_coef_[i].dot(temp);
bool valid_corr = p_body.norm() > 81 * pd2 * pd2;
if (valid_corr) {
point_selected_surf_[i] = true;
residuals_[i] = pd2;
}
}
});
}, " ObsModel (Lidar Match)");
effect_feat_num_ = 0;
corr_pts_.resize(cnt_pts);
corr_norm_.resize(cnt_pts);
for (int i = 0; i < cnt_pts; i++) {
if (point_selected_surf_[i]) {
corr_norm_[effect_feat_num_] = plane_coef_[i];
corr_pts_[effect_feat_num_] = scan_down_body_->points[i].getVector4fMap();
corr_pts_[effect_feat_num_][3] = residuals_[i];
effect_feat_num_++;
}
}
corr_pts_.resize(effect_feat_num_);
corr_norm_.resize(effect_feat_num_);
if (effect_feat_num_ < 1) {
ekfom_data.valid = false;
LOG(WARNING) << "No Effective Points!";
return;
}
Timer::Evaluate(
[&, this]() {
/*** Computation of Measurement Jacobian matrix H and measurements vector ***/
ekfom_data.h_x = Eigen::MatrixXd::Zero(effect_feat_num_, 12); // 23
ekfom_data.h.resize(effect_feat_num_);
index.resize(effect_feat_num_);
const common::M3F off_R = s.offset_R_L_I.toRotationMatrix().cast<float>();
const common::V3F off_t = s.offset_T_L_I.cast<float>();
const common::M3F Rt = s.rot.toRotationMatrix().transpose().cast<float>();
std::for_each(std::execution::par_unseq, index.begin(), index.end(), [&](const size_t &i) {
common::V3F point_this_be = corr_pts_[i].head<3>();
common::M3F point_be_crossmat = SKEW_SYM_MATRIX(point_this_be);
common::V3F point_this = off_R * point_this_be + off_t;
common::M3F point_crossmat = SKEW_SYM_MATRIX(point_this);
/*** get the normal vector of closest surface/corner ***/
common::V3F norm_vec = corr_norm_[i].head<3>();
/*** calculate the Measurement Jacobian matrix H ***/
common::V3F C(Rt * norm_vec);
common::V3F A(point_crossmat * C);
if (extrinsic_est_en_) {
common::V3F B(point_be_crossmat * off_R.transpose() * C);
ekfom_data.h_x.block<1, 12>(i, 0) << norm_vec[0], norm_vec[1], norm_vec[2], A[0], A[1], A[2], B[0],
B[1], B[2], C[0], C[1], C[2];
} else {
ekfom_data.h_x.block<1, 12>(i, 0) << norm_vec[0], norm_vec[1], norm_vec[2], A[0], A[1], A[2], 0.0,
0.0, 0.0, 0.0, 0.0, 0.0;
}
/*** Measurement: distance to the closest surface/corner ***/
ekfom_data.h(i) = -corr_pts_[i][3];
});
},
" ObsModel (IEKF Build Jacobian)");
}
///////////////////////////////////// debug save / show /////////////////////////////////////////////////////
void LaserMapping::PublishPath(const ros::Publisher pub_path) {
SetPosestamp(msg_body_pose_);
msg_body_pose_.header.stamp = ros::Time().fromSec(lidar_end_time_);
msg_body_pose_.header.frame_id = "camera_init";
/*** if path is too large, the rvis will crash ***/
path_.poses.push_back(msg_body_pose_);
if (!run_in_offline_) {
pub_path.publish(path_);
}
}
void LaserMapping::PublishOdometry(const ros::Publisher &pub_odom_aft_mapped) {
odom_aft_mapped_.header.frame_id = "camera_init";
odom_aft_mapped_.child_frame_id = "body";
odom_aft_mapped_.header.stamp = ros::Time().fromSec(lidar_end_time_); // ros::Time().fromSec(lidar_end_time_);
SetPosestamp(odom_aft_mapped_.pose);
pub_odom_aft_mapped.publish(odom_aft_mapped_);
auto P = kf_.get_P();
for (int i = 0; i < 6; i++) {
int k = i < 3 ? i + 3 : i - 3;
odom_aft_mapped_.pose.covariance[i * 6 + 0] = P(k, 3);
odom_aft_mapped_.pose.covariance[i * 6 + 1] = P(k, 4);
odom_aft_mapped_.pose.covariance[i * 6 + 2] = P(k, 5);
odom_aft_mapped_.pose.covariance[i * 6 + 3] = P(k, 0);
odom_aft_mapped_.pose.covariance[i * 6 + 4] = P(k, 1);
odom_aft_mapped_.pose.covariance[i * 6 + 5] = P(k, 2);
}
static tf::TransformBroadcaster br;
tf::Transform transform;
tf::Quaternion q;
transform.setOrigin(tf::Vector3(odom_aft_mapped_.pose.pose.position.x, odom_aft_mapped_.pose.pose.position.y,
odom_aft_mapped_.pose.pose.position.z));
q.setW(odom_aft_mapped_.pose.pose.orientation.w);
q.setX(odom_aft_mapped_.pose.pose.orientation.x);
q.setY(odom_aft_mapped_.pose.pose.orientation.y);
q.setZ(odom_aft_mapped_.pose.pose.orientation.z);
transform.setRotation(q);
br.sendTransform(tf::StampedTransform(transform, odom_aft_mapped_.header.stamp, "camera_init", "body"));
}
void LaserMapping::PublishFrameWorld() {
if (!(run_in_offline_ == false && scan_pub_en_) && !pcd_save_en_) {
return;
}
PointCloudType::Ptr laserCloudWorld;
if (dense_pub_en_) {
PointCloudType::Ptr laserCloudFullRes(scan_undistort_);
int size = laserCloudFullRes->points.size();
laserCloudWorld.reset(new PointCloudType(size, 1));
for (int i = 0; i < size; i++) {
PointBodyToWorld(&laserCloudFullRes->points[i], &laserCloudWorld->points[i]);
}
} else {
if (is_extract_large_planes_) {
laserCloudWorld = scan_down_world_other_;
int n_plane_pts = (int) scan_down_body_plane_->size();
scan_down_world_plane_->resize(n_plane_pts);
std::vector<size_t> index(n_plane_pts);
for (size_t i = 0; i < n_plane_pts; ++i) {
index[i] = i;
}
std::for_each(std::execution::unseq, index.begin(), index.end(), [&](const size_t &i) {
PointBodyToWorld(&(scan_down_body_plane_->points[i]), &(scan_down_world_plane_->points[i]));
});
*laserCloudWorld += *scan_down_world_plane_;
} else {
laserCloudWorld = scan_down_world_;
}