forked from koide3/hdl_localization
-
Notifications
You must be signed in to change notification settings - Fork 1
/
hdl_localization_nodelet.cpp
1213 lines (1019 loc) · 50.4 KB
/
hdl_localization_nodelet.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include <mutex>
#include <memory>
#include <iostream>
#include <unistd.h>
#include <typeinfo>
#include <ros/ros.h>
#include <pcl_ros/point_cloud.h>
#include <pcl_ros/transforms.h>
#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>
#include <tf2_eigen/tf2_eigen.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <eigen_conversions/eigen_msg.h>
#include <std_srvs/Empty.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/common/transforms.h>
//3rdparty includes
#include <pclomp/ndt_omp.h>
#include <pclomp/gicp_omp.h>
#include <pclomp/voxel_grid_covariance_omp.h>
// #include <fast_gicp/ndt/ndt_cuda.hpp>
// #include <fast_gicp/gicp/fast_vgicp_cuda.hpp>
#include <fast_gicp/gicp/fast_vgicp.hpp>
#include <fast_gicp/gicp/fast_vgicp_voxel.hpp>
#include <fast_gicp/gicp/fast_gicp.hpp>
#include <hdl_localization/pose_estimator.hpp>
#include <hdl_localization/delta_estimater.hpp>
#include <hdl_localization/ScanMatchingStatus.h>
#include <hdl_global_localization/SetGlobalMap.h>
#include <hdl_global_localization/QueryGlobalLocalization.h>
#include <boost/math/special_functions/round.hpp>
#include <deque>
#include <queue>
#include <map>
#include <chrono>
#include "dlo/dlo.h"
namespace hdl_localization {
class HdlLocalizationNodelet : public nodelet::Nodelet {
public:
using PointT = pcl::PointXYZI;
HdlLocalizationNodelet() : tf_buffer(), tf_listener(tf_buffer) {
}
virtual ~HdlLocalizationNodelet() {
}
// boost::shared_ptr<nano_gicp::NanoGICP<PointType, PointType> > HdlLocalizationNodelet::create_nanogicp_registration(){
// if(use_nano_gicp_){
// LOG(INFO)<<"nano_gicp is selected";
// reg_method = amr::utils::GetJsonVal<std::string>(config_.custom_config, "reg_method", "nano_gicp");
// boost::shared_ptr<nano_gicp::NanoGICP<PointType, PointType> > gicp(new nano_gicp::NanoGICP<PointType, PointType>());
// int gicps2m_k_correspondences_;
// double gicps2m_max_corr_dist_;
// int gicps2m_max_iter_;
// double gicps2m_transformation_ep_;
// double gicps2m_euclidean_fitness_ep_;
// int gicps2m_ransac_iter_;
// double gicps2m_ransac_inlier_thresh_;
// gicp_min_num_points_ = amr::utils::GetJsonVal<int>(config_.custom_config, "minNumPoints", 100);
// gicps2m_k_correspondences_ = amr::utils::GetJsonVal<int>(config_.custom_config, "kCorrespondences", 20);
// gicps2m_max_corr_dist_ = amr::utils::GetJsonVal<double>(config_.custom_config, "maxCorrespondenceDistance", 1.);
// gicps2m_max_iter_ = amr::utils::GetJsonVal<int>(config_.custom_config, "maxIterations", 32);
// gicps2m_transformation_ep_ = amr::utils::GetJsonVal<double>(config_.custom_config, "transformationEpsilon", 0.01);
// gicps2m_euclidean_fitness_ep_ = amr::utils::GetJsonVal<double>(config_.custom_config, "euclideanFitnessEpsilon", 0.01);
// gicps2m_ransac_iter_ = amr::utils::GetJsonVal<int>(config_.custom_config, "ransac_iterations", 5);
// gicps2m_ransac_inlier_thresh_ = amr::utils::GetJsonVal<double>(config_.custom_config, "ransac_outlierRejectionThresh", 1.);
// gicp->setCorrespondenceRandomness(gicps2m_k_correspondences_);
// gicp->setMaxCorrespondenceDistance(gicps2m_max_corr_dist_);
// gicp->setMaximumIterations(gicps2m_max_iter_);
// gicp->setTransformationEpsilon(gicps2m_transformation_ep_);
// gicp->setEuclideanFitnessEpsilon(gicps2m_euclidean_fitness_ep_);
// gicp->setRANSACIterations(gicps2m_ransac_iter_);
// gicp->setRANSACOutlierRejectionThreshold(gicps2m_ransac_inlier_thresh_);
// pcl::Registration<PointType, PointType>::KdTreeReciprocalPtr temp;
// gicp->setSearchMethodSource(temp, true);
// gicp->setSearchMethodTarget(temp, true);
// return gicp;
// }
// }
void onInit() override {
nh = getNodeHandle();
mt_nh = getMTNodeHandle();
private_nh = getPrivateNodeHandle();
last_scan = nullptr;
initialize_params();
robot_odom_frame_id = private_nh.param<std::string>("robot_odom_frame_id", "robot_odom");
odom_child_frame_id = private_nh.param<std::string>("odom_child_frame_id", "base_link");
use_imu = private_nh.param<bool>("use_imu", true);
invert_acc = private_nh.param<bool>("invert_acc", false);
invert_gyro = private_nh.param<bool>("invert_gyro", false);
if (use_imu) {
NODELET_INFO_STREAM("enable imu-based prediction");
imu_sub = mt_nh.subscribe("/gpsimu_driver/imu_data", 256, &HdlLocalizationNodelet::imu_callback, this);
}
points_sub = mt_nh.subscribe("/velodyne_points", 5, &HdlLocalizationNodelet::points_callback, this);
globalmap_sub = nh.subscribe("/globalmap", 1, &HdlLocalizationNodelet::globalmap_callback, this);
initialpose_sub = nh.subscribe("/initialpose", 8, &HdlLocalizationNodelet::initialpose_callback, this);
pose_pub = nh.advertise<nav_msgs::Odometry>("/hdl_result_odom", 5, false);
aligned_pub = nh.advertise<sensor_msgs::PointCloud2>("/aligned_points", 5, false);
status_pub = nh.advertise<ScanMatchingStatus>("/status", 5, false);
// global localization
use_global_localization = private_nh.param<bool>("use_global_localization", true);
if(use_global_localization) {
NODELET_INFO_STREAM("wait for global localization services");
ros::service::waitForService("/hdl_global_localization/set_global_map");
ros::service::waitForService("/hdl_global_localization/query");
set_global_map_service = nh.serviceClient<hdl_global_localization::SetGlobalMap>("/hdl_global_localization/set_global_map");
query_global_localization_service = nh.serviceClient<hdl_global_localization::QueryGlobalLocalization>("/hdl_global_localization/query");
relocalize_server = nh.advertiseService("/relocalize", &HdlLocalizationNodelet::relocalize, this);
relocalize_client = nh.serviceClient<std_srvs::Empty>("/relocalize");
// while(true){
// if(!private_nh.param<bool>("specify_init_pose", false) && last_scan){//调用"relocalize" service来初始化, 直到relocalization done
// clock_t start = clock();
// ROS_INFO("start relocalize");
// std_srvs::Empty srv;
// if(!relocalize_client.call(srv)){
// NODELET_INFO_STREAM("global localization to init hdl failed, continue to do.");
// continue;
// }else{
// clock_t end = clock();
// ROS_WARN("global localization use_time = %f ms\n\n", double(end-start)/CLOCKS_PER_SEC*1000);
// break;
// }
// }
// }
}//end use global localization
}
private:
pcl::Registration<PointT, PointT>::Ptr create_registration() const {
std::string reg_method = private_nh.param<std::string>("reg_method", "NDT_OMP");
std::string ndt_neighbor_search_method = private_nh.param<std::string>("ndt_neighbor_search_method", "DIRECT7");
double ndt_neighbor_search_radius = private_nh.param<double>("ndt_neighbor_search_radius", 2.0);
double ndt_resolution = private_nh.param<double>("ndt_resolution", 1.0);
std::string fastvgicpCUDA_nearest_neighbor_search_method = private_nh.param<std::string>("fastvgicpCUDA_nearest_neighbor_search_method", "CPU_PARALLEL_KDTREE");
int num_threads = omp_get_max_threads();
if(reg_method == "NDT_OMP") {
NODELET_INFO_STREAM("NDT_OMP is selected");
//作者ndt_omp lib
pclomp::NormalDistributionsTransform<PointT, PointT>::Ptr ndt(new pclomp::NormalDistributionsTransform<PointT, PointT>());
ndt->setNumThreads(num_threads);
ndt->setTransformationEpsilon(0.01);
ndt->setResolution(ndt_resolution);
if (ndt_neighbor_search_method == "DIRECT1") {
NODELET_INFO_STREAM("search_method DIRECT1 is selected");
ndt->setNeighborhoodSearchMethod(pclomp::DIRECT1);
} else if (ndt_neighbor_search_method == "DIRECT7") {
NODELET_INFO_STREAM("search_method DIRECT7 is selected");
ndt->setNeighborhoodSearchMethod(pclomp::DIRECT7);
} else {
if (ndt_neighbor_search_method == "KDTREE") {
NODELET_INFO_STREAM("search_method KDTREE is selected");
} else {
NODELET_WARN("invalid search method was given");
NODELET_WARN("default method is selected (KDTREE)");
}
ndt->setNeighborhoodSearchMethod(pclomp::KDTREE);
}
return ndt;
} else if(reg_method.find("NDT_CUDA") != std::string::npos) {
NODELET_INFO_STREAM("NDT_CUDA is selected");
//作者fast_gicp lib
boost::shared_ptr<fast_gicp::NDTCuda<PointT, PointT>> ndt(new fast_gicp::NDTCuda<PointT, PointT>);
ndt->setResolution(ndt_resolution);
if(reg_method.find("D2D") != std::string::npos) {
ndt->setDistanceMode(fast_gicp::NDTDistanceMode::D2D);
} else if (reg_method.find("P2D") != std::string::npos) {
ndt->setDistanceMode(fast_gicp::NDTDistanceMode::P2D);
}
if (ndt_neighbor_search_method == "DIRECT1") {
NODELET_INFO_STREAM("search_method DIRECT1 is selected");
ndt->setNeighborSearchMethod(fast_gicp::NeighborSearchMethod::DIRECT1);
} else if (ndt_neighbor_search_method == "DIRECT7") {
NODELET_INFO_STREAM("search_method DIRECT7 is selected");
ndt->setNeighborSearchMethod(fast_gicp::NeighborSearchMethod::DIRECT7);
} else if (ndt_neighbor_search_method == "DIRECT_RADIUS") {
NODELET_INFO_STREAM("search_method DIRECT_RADIUS is selected : " << ndt_neighbor_search_radius);
ndt->setNeighborSearchMethod(fast_gicp::NeighborSearchMethod::DIRECT_RADIUS, ndt_neighbor_search_radius);
} else {
NODELET_WARN("invalid search method was given");
}
return ndt; //jxl: author not add fastvgicp and corresponding cuda version, we add
}else if(reg_method.find("FastVGICP") != std::string::npos){
NODELET_INFO_STREAM("FastVGICP is selected");
boost::shared_ptr<fast_gicp::FastVGICP<PointT, PointT>> fastvgicp(new fast_gicp::FastVGICP<PointT, PointT>);
fastvgicp->setResolution(ndt_resolution);
fastvgicp->setNumThreads(num_threads);
if(reg_method.find("ADDITIVE_WEIGHTED") != std::string::npos) {
fastvgicp->setVoxelAccumulationMode(fast_gicp::VoxelAccumulationMode::ADDITIVE_WEIGHTED);
}else if(reg_method.find("MULTIPLICATIVE") != std::string::npos){
fastvgicp->setVoxelAccumulationMode(fast_gicp::VoxelAccumulationMode::MULTIPLICATIVE);
}else if(reg_method.find("ADDITIVE") != std::string::npos){
fastvgicp->setVoxelAccumulationMode(fast_gicp::VoxelAccumulationMode::ADDITIVE);
}
if (ndt_neighbor_search_method == "DIRECT1") {//见fast_vgicp_impl.hpp
NODELET_INFO_STREAM("search_method DIRECT1 is selected");
fastvgicp->setNeighborSearchMethod(fast_gicp::NeighborSearchMethod::DIRECT1);
} else if (ndt_neighbor_search_method == "DIRECT7") {
NODELET_INFO_STREAM("search_method DIRECT7 is selected");
fastvgicp->setNeighborSearchMethod(fast_gicp::NeighborSearchMethod::DIRECT7);
} else {
NODELET_WARN("invalid search method was given");
}
return fastvgicp;
}else if(reg_method.find("FastVGICP_CUDA") != std::string::npos){
NODELET_INFO_STREAM("FastVGICP_CUDA is selected");
boost::shared_ptr<fast_gicp::FastVGICPCuda<PointT, PointT>> fastvgicpCUDA(new fast_gicp::FastVGICPCuda<PointT, PointT>);
fastvgicpCUDA->setResolution(ndt_resolution);
if(reg_method.find("PLANE") != std::string::npos) { //见fast_vgicp_cuda_impl.hpp
fastvgicpCUDA->setRegularizationMethod(fast_gicp::RegularizationMethod::PLANE);
}else if(reg_method.find("FROBENIUS") != std::string::npos){
fastvgicpCUDA->setRegularizationMethod(fast_gicp::RegularizationMethod::FROBENIUS);
}else if(reg_method.find("MIN_EIG") != std::string::npos){
fastvgicpCUDA->setRegularizationMethod(fast_gicp::RegularizationMethod::MIN_EIG);
}
if (ndt_neighbor_search_method == "DIRECT1") {
NODELET_INFO_STREAM("search_method DIRECT1 is selected");
fastvgicpCUDA->setNeighborSearchMethod(fast_gicp::NeighborSearchMethod::DIRECT1, -1.0);
}else if (ndt_neighbor_search_method == "DIRECT7") {
NODELET_INFO_STREAM("search_method DIRECT7 is selected");
fastvgicpCUDA->setNeighborSearchMethod(fast_gicp::NeighborSearchMethod::DIRECT7, -1.0);
}else if(ndt_neighbor_search_method == "DIRECT27"){
NODELET_INFO_STREAM("search_method DIRECT27 is selected");
fastvgicpCUDA->setNeighborSearchMethod(fast_gicp::NeighborSearchMethod::DIRECT27, -1.0);
}else if(ndt_neighbor_search_method == "DIRECT_RADIUS"){
NODELET_INFO_STREAM("search_method DIRECT_RADIUS is selected");
fastvgicpCUDA->setNeighborSearchMethod(fast_gicp::NeighborSearchMethod::DIRECT_RADIUS, -1.0);
}
if(fastvgicpCUDA_nearest_neighbor_search_method == "CPU_PARALLEL_KDTREE"){
NODELET_INFO_STREAM("covariance CPU_PARALLEL_KDTREE is selected");
fastvgicpCUDA->setNearestNeighborSearchMethod(fast_gicp::NearestNeighborMethod::CPU_PARALLEL_KDTREE);
}else if(fastvgicpCUDA_nearest_neighbor_search_method == "GPU_BRUTEFORCE"){
NODELET_INFO_STREAM("covariance GPU_BRUTEFORCE is selected");
fastvgicpCUDA->setNearestNeighborSearchMethod(fast_gicp::NearestNeighborMethod::GPU_BRUTEFORCE);
}else if(fastvgicpCUDA_nearest_neighbor_search_method == "GPU_RBF_KERNEL"){
NODELET_INFO_STREAM("covariance GPU_RBF_KERNEL is selected");
fastvgicpCUDA->setNearestNeighborSearchMethod(fast_gicp::NearestNeighborMethod::GPU_RBF_KERNEL);
}
return fastvgicpCUDA;
}
else if(reg_method.find("FastGICP") != std::string::npos){
LOG(INFO)<<"FastGICP is selected";
boost::shared_ptr<fast_gicp::FastGICP<PointT, PointT>> fastgicp(new fast_gicp::FastGICP<PointT, PointT>);
fastgicp->setNumThreads(num_threads);
return fastgicp;
}
NODELET_ERROR_STREAM("unknown registration method:" << reg_method);
return nullptr;
}
void initialize_params() {
// intialize scan matching method
hdl_result_odom = std::string("hdl_result_odom");
wheel_odom_hdl_result_odom = std::string("wheel_odom_hdl_result_odom");
double downsample_resolution = private_nh.param<double>("downsample_resolution", 0.1);
boost::shared_ptr<pcl::VoxelGrid<PointT>> voxelgrid(new pcl::VoxelGrid<PointT>());
voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
downsample_filter = voxelgrid;
NODELET_INFO_STREAM("create registration method for localization");
// use_nano_gicp_ = amr::utils::GetJsonVal<int>(config_.custom_config, "use_nano_gicp", true);
// if(use_nano_gicp_){
// nanogicp_registration = create_nanogicp_registration();
// }else{
// registration = create_registration();
// }
registration = create_registration();
// global localization
NODELET_INFO_STREAM("create registration method for fallback during relocalization");
relocalizing = false;
delta_estimater.reset(new DeltaEstimater(create_registration()));
// initialize pose estimator
if(private_nh.param<bool>("specify_init_pose", true)) {
NODELET_INFO_STREAM("initialize pose estimator with specified parameters!!");
// jxl: adaptor to with nano_gicp when create pose_estimator.
// if(use_nano_gicp_){
// pose_estimator.reset(new PoseEstimator(nanogicp_registration, ros::Time::now(), position, rot, use_nano_gicp_, cool_time));
// }else{
// use registration
// }
pose_estimator.reset(new hdl_localization::PoseEstimator(
registration,
ros::Time::now(),
Eigen::Vector3f(private_nh.param<double>("init_pos_x", 0.0), private_nh.param<double>("init_pos_y", 0.0), private_nh.param<double>("init_pos_z", 0.0)),
Eigen::Quaternionf(private_nh.param<double>("init_ori_w", 1.0), private_nh.param<double>("init_ori_x", 0.0), private_nh.param<double>("init_ori_y", 0.0), private_nh.param<double>("init_ori_z", 0.0)),
private_nh.param<double>("cool_time_duration", 0.5)
));
}
}
private:
void remove_nanpoints(pcl::PointCloud<PointT>::Ptr pcl_cloud){
pcl_cloud->is_dense = false;
std::vector<int> indices;
auto size0 = pcl_cloud->points.size();
pcl::removeNaNFromPointCloud(*pcl_cloud, *pcl_cloud, indices);
auto size1 = pcl_cloud->points.size();
if(size0 != size1)
LOG(INFO)<<"RemoveNaN delete "<<fabs(size0 - size1)<<" points, percentage = "<< fabs(size0 - size1)/(size0*1.0)*100<<"%";
size0 = size1;
size1 = 0;
pcl::PointCloud<PointT>::iterator it = pcl_cloud->points.begin();
while (it != pcl_cloud->points.end()){
float x, y, z, intensity;
x = it->x;
y = it->y;
z = it->z;
intensity =it->intensity;
if (!pcl_isfinite(x) || !pcl_isfinite(y) || !pcl_isfinite(z) || !pcl_isfinite(intensity)){
it = pcl_cloud->points.erase(it);
}
else{
++it;
size1++;
}
}
if(size0 != size1)
LOG(INFO)<<"Isfinite remove "<<fabs(size0 - size1)<<" points, percentage = "<< fabs(size0 - size1)/(size0*1.0)*100<<"%";
return;
}
/**
* @brief callback for imu data
* @param imu_msg
*/
void imu_callback(const sensor_msgs::ImuConstPtr& imu_msg) {
{
std::unique_lock<std::mutex> lock(imu_data_mutex);
imu_data.push_back(imu_msg);
imu_received = true;
}
while(use_global_localization && !initialized){
if(!private_nh.param<bool>("specify_init_pose", false) && last_scan){//调用"relocalize" service来初始化, 直到relocalization done
clock_t start = clock();
ROS_INFO("start relocalize");
std_srvs::Empty srv;
if(!relocalize_client.call(srv)){
NODELET_INFO_STREAM("global localization to init hdl failed, continue to do.");
continue;
}else{
clock_t end = clock();
ROS_WARN("global localization use_time = %f ms\n\n", double(end-start)/CLOCKS_PER_SEC*1000);
break;
}
}
}
}
/**
* @brief callback for point cloud data
* @param points_msg
*/
void points_callback(const sensor_msgs::PointCloud2ConstPtr& points_msg) {
std::unique_lock<std::mutex> estimator_lock(pose_estimator_mutex);
if(use_global_localization){
if(last_scan && !initialized){
NODELET_INFO_STREAM("wait for init");
return;
}
//use the first laser to init when we use "relocalize" to init
if(!initialized && !private_nh.param<bool>("specify_init_pose", false) ) {
NODELET_INFO_STREAM("set first laser scan");
const auto& stamp = points_msg->header.stamp;
pcl::PointCloud<PointT>::Ptr pcl_cloud(new pcl::PointCloud<PointT>());
pcl::fromROSMsg(*points_msg, *pcl_cloud);
if(pcl_cloud->empty()) {
NODELET_ERROR("cloud is empty!!");
return;
}
pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
if(odom_child_frame_id.compare(points_msg->header.frame_id) == 0){
cloud = pcl_cloud;
}
else{
if(!pcl_ros::transformPointCloud(odom_child_frame_id, *pcl_cloud, *cloud, this->tf_buffer)) {
NODELET_ERROR("point cloud cannot be transformed into target frame!!");
return;
}
}
auto filtered = downsample(cloud);
last_scan = filtered;
NODELET_INFO_STREAM("set first laser scan done");
return;
}
}
if(!pose_estimator) {
NODELET_ERROR("waiting for initial pose input!!");
return;
}
if(!globalmap) {
NODELET_ERROR("globalmap has not been received!!");
return;
}
const auto& stamp = points_msg->header.stamp;
pcl::PointCloud<PointT>::Ptr pcl_cloud(new pcl::PointCloud<PointT>());
pcl::fromROSMsg(*points_msg, *pcl_cloud);
remove_nanpoints(pcl_cloud);
if(pcl_cloud->empty()) {
NODELET_ERROR("cloud is empty!!");
return;
}
// transform pointcloud into odom_child_frame_id
pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
// if(!pcl_ros::transformPointCloud(odom_child_frame_id, *pcl_cloud, *cloud, this->tf_buffer)) {
// NODELET_ERROR("point cloud cannot be transformed into target frame!!");
// return;
// }
//进来的laser points本来就在laser frame下, 可以不用再转换
if(odom_child_frame_id.compare(points_msg->header.frame_id) == 0){
cloud = pcl_cloud;
}
else{
if(!pcl_ros::transformPointCloud(odom_child_frame_id, *pcl_cloud, *cloud, this->tf_buffer)) {
NODELET_ERROR("point cloud cannot be transformed into target frame!!");
return;
}
}
auto filtered = downsample(cloud);
last_scan = filtered;
// ROS_INFO("In laser callback, relocalizing = %d\n", relocalizing.load()) ;
//从用户调用"/relocalize" 服务到服务response 返回前, relocalizing = true;
//response返回后, relocalizing = false;
//如果一直不调用relocalize, relocalizing会一直为false;
if(relocalizing) { //调用了重定位, 但是结果还未返回. 在这段时间的laser callback中relocalizing = 1
delta_estimater->add_frame(filtered);
//假设relocalization发生在k时刻laser, 过了delta_t时间后response返回, 在这段时间, laser的回调函数不断在丢失了的历史位姿上执行ukf
//delta_estimater->estimated_delta(): 计算k时刻laser 到当前时刻laser(k + delta_t)的变换.
}
Eigen::Matrix4f before = pose_estimator->matrix(); //ukf mean中PQ分量
// predict
if(!use_imu) {
pose_estimator->predict(stamp); //用常量速度模型把从estimator状态从上一帧时刻预测到当前帧时刻
} else {
std::unique_lock<std::mutex> lock(imu_data_mutex);
if(!imu_received){
std::cout<<"\033[31m"<<"Enable imu but not received imu!!!\n";
return;
}
if(imu_data.empty() == false){
auto imu_iter = imu_data.begin();
for(imu_iter; imu_iter != imu_data.end(); imu_iter++) {
if(stamp < (*imu_iter)->header.stamp) {
break;
}
const auto& acc = (*imu_iter)->linear_acceleration;
const auto& gyro = (*imu_iter)->angular_velocity;
double acc_sign = invert_acc ? -1.0 : 1.0;
double gyro_sign = invert_gyro ? -1.0 : 1.0;
pose_estimator->predict((*imu_iter)->header.stamp,
acc_sign * Eigen::Vector3f(acc.x, acc.y, acc.z),
gyro_sign * Eigen::Vector3f(gyro.x, gyro.y, gyro.z));
//上一帧laser到当前帧laser之间的所有imu meas都用来做predict
}
imu_data.erase(imu_data.begin(), imu_iter);
}
}
// odometry-based prediction
//得有其他第三方模块不停地在发布"odom" ---> "velodyne" TF
ros::Time last_correction_time = pose_estimator->last_correction_time();
if(private_nh.param<bool>("enable_robot_odometry_prediction", false) && !last_correction_time.isZero()) {
geometry_msgs::TransformStamped odom_delta;
if(tf_buffer.canTransform(odom_child_frame_id, last_correction_time, odom_child_frame_id, stamp, robot_odom_frame_id, ros::Duration(0.1))) {
odom_delta = tf_buffer.lookupTransform(odom_child_frame_id, last_correction_time, odom_child_frame_id, stamp, robot_odom_frame_id, ros::Duration(0));
} else if(tf_buffer.canTransform(odom_child_frame_id, last_correction_time, odom_child_frame_id, ros::Time(0), robot_odom_frame_id, ros::Duration(0))) {
odom_delta = tf_buffer.lookupTransform(odom_child_frame_id, last_correction_time, odom_child_frame_id, ros::Time(0), robot_odom_frame_id, ros::Duration(0));
}
if(odom_delta.header.stamp.isZero()) {
NODELET_WARN_STREAM("failed to look up transform between " << cloud->header.frame_id << " and " << robot_odom_frame_id);
} else {
Eigen::Isometry3d delta = tf2::transformToEigen(odom_delta); //velodyne: last_correction_time ---> 当前帧时刻的velodyne变换
pose_estimator->predict_odom(delta.cast<float>().matrix());
}
}
// correct
auto aligned = pose_estimator->correct(stamp, filtered);
remove_nanpoints(aligned);
if(aligned->empty()) {
std::cout<<"Result cloud is empty!!";
return;
}
//processed_laser_num ++;
if(aligned_pub.getNumSubscribers()) {
aligned->header.frame_id = "map";
aligned->header.stamp = cloud->header.stamp;
aligned_pub.publish(aligned);
}
if(status_pub.getNumSubscribers()) {
publish_scan_matching_status(points_msg->header, aligned);
}
publish_odometry(points_msg->header.stamp, pose_estimator->matrix());
// publish_odometry(points_msg->header.stamp,
// pose_estimator->matrix(), pose_estimator->cov(), hdl_result_odom);
// publish_odometry(points_msg->header.stamp,
// pose_estimator->odom_matrix(), pose_estimator->odom_cov(), wheel_odom_hdl_result_odom);
}
/**
* @brief callback for globalmap input
* @param points_msg
*/
//把global map设置到ukf estimator的registration中(通过引用实现)
// 和重定位service 的global_map中
void globalmap_callback(const sensor_msgs::PointCloud2ConstPtr& points_msg) {
std::unique_lock<std::mutex> lock(pose_estimator_mutex);
ROS_INFO("receive globalmap topic!");
pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
pcl::fromROSMsg(*points_msg, *cloud);
globalmap = cloud;
registration->setInputTarget(globalmap);
// if(use_nano_gicp_){
// nanogicp_registration->setInputTarget(globalmap);
// }else{
// registration->setInputTarget(globalmap);
// }
while(!set_global_map_done && use_global_localization){
NODELET_INFO_STREAM("set globalmap for global localization!");
hdl_global_localization::SetGlobalMap srv;
pcl::toROSMsg(*globalmap, srv.request.global_map);
ROS_WARN("start set global map");
clock_t start = clock();
if(!set_global_map_service.call(srv)) {
NODELET_INFO_STREAM("failed to set global map");
set_global_map_done = false;
} else {
set_global_map_done = true;
NODELET_INFO_STREAM("set global map done");
clock_t end = clock();
ROS_WARN("set global map use_time = %f ms", double(end-start)/CLOCKS_PER_SEC*1000);
}
}
ROS_INFO("globalmap done");
}
// tf2::Transform lookup_pose(const rclcpp::Time& time){
// std::unique_lock<std::mutex> odom_lock(odom_mutex);
// tf2::Transform result;
// auto key = time.nanoseconds();
// if(odom_data.lower_bound(key) != odom_data.end()){ //returns an iterator to the first element not less than the given key
// auto outcome = odom_data.lower_bound(key);
// if(outcome == odom_data.begin()){
// LOG(INFO)<<"\033[33m"<<"Smallest data greater than "<< static_cast<double>((outcome->first - key)*1e-6)<<" ms"<<"\033[0m"<<"\n";
// nav_msgs::msg::Odometry tmp = *(outcome->second);
// result.setOrigin(tf2::Vector3(tmp.pose.pose.position.x,
// tmp.pose.pose.position.y,
// tmp.pose.pose.position.z));
// result.setRotation(tf2::Quaternion(tmp.pose.pose.orientation.x,
// tmp.pose.pose.orientation.y,
// tmp.pose.pose.orientation.z,
// tmp.pose.pose.orientation.w));
// }else{
// LOG(INFO)<<"Buffer index="<< std::distance(odom_data.begin(), outcome)<<" find of "<<std::distance(odom_data.begin(), --(odom_data.end()))<<"\n";
// auto next_it = outcome;
// --outcome;
// auto prev_it = outcome;
// auto s1 = fabs(static_cast<double>((key - prev_it->first)*1e-9));
// auto s2 = fabs(static_cast<double>((next_it->first - key)*1e-9));
// auto s = fabs(static_cast<double>((next_it->first - prev_it->first)*1e-9));
// auto next = *(next_it->second);
// auto prev = *(prev_it->second);
// double x = prev.pose.pose.position.x * (s2 / s) + next.pose.pose.position.x * (s1 / s);
// double y = prev.pose.pose.position.y * (s2 / s) + next.pose.pose.position.y * (s1 / s);
// double z = prev.pose.pose.position.z * (s2 / s) + next.pose.pose.position.z * (s1 / s);
// tf2::Quaternion a(prev.pose.pose.orientation.x,
// prev.pose.pose.orientation.y,
// prev.pose.pose.orientation.z,
// prev.pose.pose.orientation.w);
// tf2::Quaternion b(next.pose.pose.orientation.x,
// next.pose.pose.orientation.y,
// next.pose.pose.orientation.z,
// next.pose.pose.orientation.w);
// tf2::Quaternion q = a.slerp(b, s1 / s);
// result.setOrigin(tf2::Vector3(x, y, z));
// result.setRotation(tf2::Quaternion(q));
// }
// }else{
// auto end_it = (--odom_data.end());
// LOG(INFO)<<"\033[33m"<<"Bigest data less than "<<static_cast<double>((key - end_it->first)*1e-6)<<" ms"<<"\033[0m"<<"\n";
// nav_msgs::msg::Odometry tmp= *(end_it->second);
// result.setOrigin(tf2::Vector3(tmp.pose.pose.position.x,
// tmp.pose.pose.position.y,
// tmp.pose.pose.position.z));
// result.setRotation(tf2::Quaternion(tmp.pose.pose.orientation.x,
// tmp.pose.pose.orientation.y,
// tmp.pose.pose.orientation.z,
// tmp.pose.pose.orientation.w));
// }
// return result;
// }
// Eigen::Isometry3d lookup_deltaT(const rclcpp::Time& last_time, const rclcpp::Time& curr_time){
// tf2::Transform T1 = lookup_pose(last_time);
// tf2::Transform T1_inv = T1.inverse();
// tf2::Transform T2 = lookup_pose(curr_time);
// tf2::Transform delta = T1_inv * T2;
// auto xyz = T1.getOrigin();
// double r, p, y;
// T1.getBasis().getRPY(r,p,y);
// r *= 180/M_PI;
// p *= 180/M_PI;
// y *= 180/M_PI;
// //LOG(INFO)<<"last time pose: xyz= "<<xyz.getX()<<" "<<xyz.getY()<<" "<<xyz.getZ()<<"; rpy= "<<r<<" "<<p<<" "<<y<<"\n";
// xyz = T1_inv.getOrigin();
// T1_inv.getBasis().getRPY(r,p,y);
// r *= 180/M_PI;
// p *= 180/M_PI;
// y *= 180/M_PI;
// xyz = T2.getOrigin();
// T2.getBasis().getRPY(r,p,y);
// r *= 180/M_PI;
// p *= 180/M_PI;
// y *= 180/M_PI;
// //LOG(INFO)<<"curr_time pose: xyz= "<<xyz.getX()<<" "<<xyz.getY()<<" "<<xyz.getZ()<<"; rpy= "<<r<<" "<<p<<" "<<y<<"\n";
// xyz = delta.getOrigin();
// delta.getBasis().getRPY(r,p,y);
// r *= 180/M_PI;
// p *= 180/M_PI;
// y *= 180/M_PI;
// LOG(INFO)<<"delta pose: xyz= "<<xyz.getX()<<" "<<xyz.getY()<<" "<<xyz.getZ()<<"; rpy= "<<r<<" "<<p<<" "<<y<<"\n";
// return tf2::transformToEigen(tf2::toMsg(delta));
// }
/**
* @brief perform global localization to relocalize the sensor position
* @param
*/
bool relocalize(std_srvs::EmptyRequest& req, std_srvs::EmptyResponse& res) {
//默认重定位服务函数在执行前, 不获得 pose_estimator_mutex.
std::unique_lock<std::mutex> estimator_lock(pose_estimator_mutex);
//如果laser的回调函数正在执行, 该服务就得等到laser callback执行完毕才执行
//1: 如果初值决定要手动由rosservice call /relocalize 给, 该服务回调函数基本上执行不上,
// 导致pose_estimator一直为nullptr, 也会导致laser 回调函数一直"waiting for initial pose input!!"
//TODO(jxl): 是个bug, we fixed it, https://github.com/koide3/hdl_localization/issues/68
//2: 如果初值还是由/initialpose" 给定, 发现定位丢失后(匹配的error大于一定值, or ukf 输出的covariance大于一定阈值),
//用rosservice call /relocalize 来reset ukf estimator.
NODELET_INFO_STREAM("enter global localization");
if(!set_global_map_done){
NODELET_INFO_STREAM("wait for set global map complete");
return false;
}
NODELET_INFO_STREAM("global map done");
if(last_scan == nullptr) {
NODELET_INFO_STREAM("no scan has been received");
return false;
}
NODELET_INFO_STREAM("last_scan not nullptr");
relocalizing = true;
delta_estimater->reset(); //每次relocalize计算前, reset delta_estimater
pcl::PointCloud<PointT>::ConstPtr scan = last_scan;
hdl_global_localization::QueryGlobalLocalization srv;
pcl::toROSMsg(*scan, srv.request.cloud);
srv.request.max_num_candidates = 1;
ROS_WARN("query global localize");
if(!query_global_localization_service.call(srv) || srv.response.poses.empty()) {
relocalizing = false;
NODELET_INFO_STREAM("global localization failed");
return false;
}
const auto& result = srv.response.poses[0];
NODELET_INFO_STREAM("--- Global localization result ---");
NODELET_INFO_STREAM("Trans :" << result.position.x << " " << result.position.y << " " << result.position.z);
NODELET_INFO_STREAM("Quat :" << result.orientation.x << " " << result.orientation.y << " " << result.orientation.z << " " << result.orientation.w);
NODELET_INFO_STREAM("Error :" << srv.response.errors[0]);
NODELET_INFO_STREAM("Inlier:" << srv.response.inlier_fractions[0]);
Eigen::Isometry3f pose = Eigen::Isometry3f::Identity();
pose.linear() = Eigen::Quaternionf(result.orientation.w, result.orientation.x, result.orientation.y, result.orientation.z).toRotationMatrix();
pose.translation() = Eigen::Vector3f(result.position.x, result.position.y, result.position.z);
pose = pose * delta_estimater->estimated_delta();
//重定位时刻所用的laser帧 和当前laser的回调函数已经正在执行的laser帧已经过去了delta_t
// jxl: adaptor to with nano_gicp when create pose_estimator.
// if(use_nano_gicp_){
// pose_estimator.reset(new PoseEstimator(nanogicp_registration, ros::Time::now(), position, rot, use_nano_gicp_, cool_time));
// }else{
// use registration
// }
// std::unique_lock<std::mutex> lock(pose_estimator_mutex); //default
pose_estimator.reset(new hdl_localization::PoseEstimator( //用重定位的结果reset ukf estimator
registration,
ros::Time::now(),
pose.translation(),
Eigen::Quaternionf(pose.linear()),
private_nh.param<double>("cool_time_duration", 0.5)));
relocalizing = false;
if( !private_nh.param<bool>("specify_init_pose", false) ){
initialized = true;
}
ROS_INFO("========Relocalization done========");
return true;
}
/**
* @brief callback for initial pose input ("2D Pose Estimate" on rviz)
* @param pose_msg
*/
void initialpose_callback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose_msg) {
NODELET_INFO_STREAM("initial pose received!!");
std::unique_lock<std::mutex> lock(pose_estimator_mutex);
const auto& p = pose_msg->pose.pose.position;
const auto& q = pose_msg->pose.pose.orientation;
// jxl: adaptor to with nano_gicp when create pose_estimator.
// if(use_nano_gicp_){
// pose_estimator.reset(new PoseEstimator(nanogicp_registration, ros::Time::now(), position, rot, use_nano_gicp_, cool_time));
// }else{
// use registration
// }
pose_estimator.reset( //创建ukf estimator
new hdl_localization::PoseEstimator(
registration,
ros::Time::now(),
Eigen::Vector3f(p.x, p.y, p.z),
Eigen::Quaternionf(q.w, q.x, q.y, q.z), //初始值作为estimator 0时刻的状态
private_nh.param<double>("cool_time_duration", 0.5))
);
initialized = true;
}
/**
* @brief downsampling
* @param cloud input cloud
* @return downsampled cloud
*/
pcl::PointCloud<PointT>::ConstPtr downsample(const pcl::PointCloud<PointT>::ConstPtr& cloud) const {
if(!downsample_filter) {
return cloud;
}
pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());
downsample_filter->setInputCloud(cloud);
downsample_filter->filter(*filtered);
filtered->header = cloud->header;
return filtered;
}
/**
* @brief publish odometry
* @param stamp timestamp
* @param pose odometry pose to be published
*/
void publish_odometry(const ros::Time& stamp, const Eigen::Matrix4f& pose) {
// broadcast the transform over tf
//有其他第三方模块不停地在发布"odom" ---> "velodyne" TF
if(tf_buffer.canTransform(robot_odom_frame_id, odom_child_frame_id, ros::Time(0))) {
geometry_msgs::TransformStamped map_wrt_frame = tf2::eigenToTransform(Eigen::Isometry3d(pose.inverse().cast<double>()));
map_wrt_frame.header.stamp = stamp;
map_wrt_frame.header.frame_id = odom_child_frame_id;
map_wrt_frame.child_frame_id = "map";
geometry_msgs::TransformStamped frame_wrt_odom = tf_buffer.lookupTransform(robot_odom_frame_id, odom_child_frame_id, ros::Time(0), ros::Duration(0.1));
Eigen::Matrix4f frame2odom = tf2::transformToEigen(frame_wrt_odom).cast<float>().matrix();
geometry_msgs::TransformStamped map_wrt_odom; //map_wrt_odom = frame_wrt_odom * map_wrt_frame
tf2::doTransform(map_wrt_frame, map_wrt_odom, frame_wrt_odom);
tf2::Transform odom_wrt_map;
tf2::fromMsg(map_wrt_odom.transform, odom_wrt_map);
odom_wrt_map = odom_wrt_map.inverse();
geometry_msgs::TransformStamped odom_trans;
odom_trans.transform = tf2::toMsg(odom_wrt_map); //map ---> odom
odom_trans.header.stamp = stamp;
odom_trans.header.frame_id = "map";
odom_trans.child_frame_id = robot_odom_frame_id;
tf_broadcaster.sendTransform(odom_trans);
} else {
geometry_msgs::TransformStamped odom_trans = tf2::eigenToTransform(Eigen::Isometry3d(pose.cast<double>()));
odom_trans.header.stamp = stamp;
odom_trans.header.frame_id = "map";
odom_trans.child_frame_id = odom_child_frame_id;
tf_broadcaster.sendTransform(odom_trans); //map ---> laser
}
// publish the transform
nav_msgs::Odometry odom;
odom.header.stamp = stamp;
odom.header.frame_id = "map";
tf::poseEigenToMsg(Eigen::Isometry3d(pose.cast<double>()), odom.pose.pose);
odom.child_frame_id = odom_child_frame_id;
odom.twist.twist.linear.x = 0.0;
odom.twist.twist.linear.y = 0.0;
odom.twist.twist.angular.z = 0.0;
// odom.pose.covariance[0] = cov(0, 0);
// odom.pose.covariance[7] = cov(1, 1);
// odom.pose.covariance[14] = cov(2, 2); //position cov; //TODO(jxl): rot cov
// io_->Publish<nav_msgs::msg::Odometry>(name, odom); //"/odom" topic发布map--->laser的位姿
// geometry_msgs::msg::PoseStamped pose_stamped;
// pose_stamped.header.stamp = odom.header.stamp;
// pose_stamped.header.frame_id = odom.header.frame_id;
// pose_stamped.pose = odom.pose.pose;
// if( name.compare(hdl_result_odom) == 0 ){
// std::unique_lock<std::mutex>(localize_path_mutex);
// localize_path.poses.push_back(pose_stamped);
// localize_path.header.stamp = odom.header.stamp;
// localize_path.header.frame_id = odom.header.frame_id;
// io_->Publish<nav_msgs::msg::Path>("localize_path", localize_path);
// }else if(name.compare(wheel_odom_hdl_result_odom) == 0){
// std::unique_lock<std::mutex>(odom_localize_path_mutex);
// odom_localize_path.poses.push_back(pose_stamped);
// odom_localize_path.header.stamp = odom.header.stamp;
// odom_localize_path.header.frame_id = odom.header.frame_id;
// io_->Publish<nav_msgs::msg::Path>("odom_localize_path", odom_localize_path);
// }
pose_pub.publish(odom); //"/odom" topic发布map--->laser的位姿
}
// void save_localize_path(const std::shared_ptr<const std_msgs::msg::String> msgIn){
// static bool saved = false;
// if(saved)
// return;
// std::unique_lock<std::mutex>(localize_path_mutex);
// std::string path = amr::utils::GetJsonVal<std::string>(config_.custom_config, "localize_path", "/tmp/");
// std::string imu_flag = use_imu ? std::string("imu_") : std::string("");
// std::string odom_flag = odom_predict ? std::string("odom_") : std::string("");
// std::string name = path + imu_flag + odom_flag + reg_method +"_localize_result.txt";
// std::ofstream file = std::ofstream(name, std::ios_base::out);
// for(auto& it : localize_path.poses){
// file<<tf2_ros::timeToSec(it.header.stamp)<<" "<<it.pose.position.x<<" "<<it.pose.position.y<<" "<<it.pose.position.z<<" "
// <<it.pose.orientation.x<<" "<<it.pose.orientation.y<<" "<<it.pose.orientation.z<<" "<<it.pose.orientation.w<<std::endl;
// }
// file.close();
// saved = true;
// LOG(INFO) << "Saving localize result to file completed ..." << std::endl;
// LOG(INFO) << "****************************************************" << std::endl;
// return;
// }
/**
* @brief publish scan matching status information
*/
void publish_scan_matching_status(const std_msgs::Header& header, pcl::PointCloud<pcl::PointXYZI>::ConstPtr aligned) {
ScanMatchingStatus status;
status.header = header;
status.has_converged = registration->hasConverged();
status.matching_error = registration->getFitnessScore();
const double max_correspondence_dist = 0.5;
int num_inliers = 0;
std::vector<int> k_indices;
std::vector<float> k_sq_dists;
for(int i = 0; i < aligned->size(); i++) {
const auto& pt = aligned->at(i);
registration->getSearchMethodTarget()->nearestKSearch(pt, 1, k_indices, k_sq_dists);
if(k_sq_dists[0] < max_correspondence_dist * max_correspondence_dist) {
num_inliers++;
}
}
status.inlier_fraction = static_cast<float>(num_inliers) / aligned->size();
status.relative_pose = tf2::eigenToTransform(Eigen::Isometry3d(registration->getFinalTransformation().cast<double>())).transform;
status.prediction_labels.reserve(2);
status.prediction_errors.reserve(2);
std::vector<double> errors(6, 0.0);
if(pose_estimator->wo_prediction_error()) {
status.prediction_labels.push_back(std_msgs::String());
status.prediction_labels.back().data = "without_pred";
status.prediction_errors.push_back(tf2::eigenToTransform(Eigen::Isometry3d(pose_estimator->wo_prediction_error().get().cast<double>())).transform);
}
if(pose_estimator->imu_prediction_error()) {
status.prediction_labels.push_back(std_msgs::String());
status.prediction_labels.back().data = use_imu ? "imu" : "motion_model";
status.prediction_errors.push_back(tf2::eigenToTransform(Eigen::Isometry3d(pose_estimator->imu_prediction_error().get().cast<double>())).transform);
}
if(pose_estimator->odom_prediction_error()) {
status.prediction_labels.push_back(std_msgs::String());
status.prediction_labels.back().data = "odom";
status.prediction_errors.push_back(tf2::eigenToTransform(Eigen::Isometry3d(pose_estimator->odom_prediction_error().get().cast<double>())).transform);
}
status_pub.publish(status);
}