diff --git a/config/avia.yaml b/config/avia.yaml
index 2f3d43d..a98aa4e 100644
--- a/config/avia.yaml
+++ b/config/avia.yaml
@@ -21,7 +21,13 @@ mapping:
0, 1, 0,
0, 0, 1]
-publish:
+publish:
+ path_en: false
scan_publish_en: true # false: close all the point cloud output
dense_publish_en: true # false: low down the points number in a global-frame point clouds scan.
- scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
\ No newline at end of file
+ scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
+
+pcd_save:
+ pcd_save_en: true
+ interval: -1 # how many LiDAR frames saved in each pcd file;
+ # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
\ No newline at end of file
diff --git a/config/horizon.yaml b/config/horizon.yaml
index 4f10865..b7bc637 100644
--- a/config/horizon.yaml
+++ b/config/horizon.yaml
@@ -21,7 +21,13 @@ mapping:
0, 1, 0,
0, 0, 1]
-publish:
+publish:
+ path_en: false
scan_publish_en: true # false: close all the point cloud output
dense_publish_en: true # false: low down the points number in a global-frame point clouds scan.
- scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
\ No newline at end of file
+ scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
+
+pcd_save:
+ pcd_save_en: true
+ interval: -1 # how many LiDAR frames saved in each pcd file;
+ # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
\ No newline at end of file
diff --git a/config/ouster64.yaml b/config/ouster64.yaml
index a404d29..3f7f8f0 100644
--- a/config/ouster64.yaml
+++ b/config/ouster64.yaml
@@ -21,7 +21,13 @@ mapping:
0, 1, 0,
0, 0, 1]
-publish:
+publish:
+ path_en: false
scan_publish_en: true # false: close all the point cloud output
dense_publish_en: true # false: low down the points number in a global-frame point clouds scan.
- scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
\ No newline at end of file
+ scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
+
+pcd_save:
+ pcd_save_en: true
+ interval: -1 # how many LiDAR frames saved in each pcd file;
+ # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
\ No newline at end of file
diff --git a/config/velodyne.yaml b/config/velodyne.yaml
index a00ad83..006ed96 100644
--- a/config/velodyne.yaml
+++ b/config/velodyne.yaml
@@ -21,7 +21,13 @@ mapping:
0, 1, 0,
0, 0, 1]
-publish:
+publish:
+ path_en: false
scan_publish_en: true # false: close all the point cloud output
dense_publish_en: true # false: low down the points number in a global-frame point clouds scan.
- scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
\ No newline at end of file
+ scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
+
+pcd_save:
+ pcd_save_en: true
+ interval: -1 # how many LiDAR frames saved in each pcd file;
+ # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
\ No newline at end of file
diff --git a/launch/mapping_avia.launch b/launch/mapping_avia.launch
index afcb0ce..9c5ea00 100644
--- a/launch/mapping_avia.launch
+++ b/launch/mapping_avia.launch
@@ -6,13 +6,12 @@
-
+
-
diff --git a/launch/mapping_horizon.launch b/launch/mapping_horizon.launch
index 0e0a8c2..17b6d63 100644
--- a/launch/mapping_horizon.launch
+++ b/launch/mapping_horizon.launch
@@ -7,13 +7,12 @@
-
+
-
-
+
diff --git a/launch/mapping_ouster64.launch b/launch/mapping_ouster64.launch
index 0e7340b..1f5a2a5 100644
--- a/launch/mapping_ouster64.launch
+++ b/launch/mapping_ouster64.launch
@@ -12,7 +12,6 @@
-
diff --git a/launch/mapping_velodyne.launch b/launch/mapping_velodyne.launch
index 6567946..25d449c 100644
--- a/launch/mapping_velodyne.launch
+++ b/launch/mapping_velodyne.launch
@@ -12,7 +12,6 @@
-
diff --git a/src/laserMapping.cpp b/src/laserMapping.cpp
index f8d2c95..d599481 100644
--- a/src/laserMapping.cpp
+++ b/src/laserMapping.cpp
@@ -70,7 +70,7 @@ double kdtree_incremental_time = 0.0, kdtree_search_time = 0.0, kdtree_delete_ti
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;
+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};
@@ -89,7 +89,7 @@ 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;
+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_reset, flg_exit = false, flg_EKF_inited;
bool scan_pub_en = false, dense_pub_en = false, scan_body_pub_en = false;
@@ -479,7 +479,7 @@ void publish_frame_world(const ros::Publisher & pubLaserCloudFull)
/**************** save map ****************/
/* 1. make sure you have enough memories
- /* 2. pcd save will largely influence the real-time performences **/
+ /* 2. noted that pcd save will influence the real-time performences **/
if (pcd_save_en)
{
int size = feats_undistort->points.size();
@@ -492,6 +492,19 @@ void publish_frame_world(const ros::Publisher & pubLaserCloudFull)
&laserCloudWorld->points[i]);
}
*pcl_wait_save += *laserCloudWorld;
+
+ static int scan_wait_num = 0;
+ scan_wait_num ++;
+ if (pcl_wait_save->size() > 0 && pcd_save_interval > 0 && scan_wait_num >= pcd_save_interval)
+ {
+ pcd_index ++;
+ string all_points_dir(string(string(ROOT_DIR) + "PCD/scans_") + to_string(pcd_index) + string(".pcd"));
+ pcl::PCDWriter pcd_writer;
+ cout << "current scan saved to /PCD/" << all_points_dir << endl;
+ pcd_writer.writeBinary(all_points_dir, *pcl_wait_save);
+ pcl_wait_save->clear();
+ scan_wait_num = 0;
+ }
}
}
@@ -717,9 +730,10 @@ int main(int argc, char** argv)
ros::init(argc, argv, "laserMapping");
ros::NodeHandle nh;
- nh.param("publish/scan_publish_en",scan_pub_en,1);
- nh.param("publish/dense_publish_en",dense_pub_en,1);
- nh.param("publish/scan_bodyframe_pub_en",scan_body_pub_en,1);
+ nh.param("publish/path_en",path_en, true);
+ nh.param("publish/scan_publish_en",scan_pub_en, true);
+ nh.param("publish/dense_publish_en",dense_pub_en, true);
+ nh.param("publish/scan_bodyframe_pub_en",scan_body_pub_en, true);
nh.param("max_iteration",NUM_MAX_ITERATIONS,4);
nh.param("map_file_path",map_file_path,"");
nh.param("common/lid_topic",lid_topic,"/livox/lidar");
@@ -739,10 +753,11 @@ int main(int argc, char** argv)
nh.param("preprocess/lidar_type", p_pre->lidar_type, AVIA);
nh.param("preprocess/scan_line", p_pre->N_SCANS, 16);
nh.param("point_filter_num", p_pre->point_filter_num, 2);
- nh.param("feature_extract_enable", p_pre->feature_enabled, 0);
+ nh.param("feature_extract_enable", p_pre->feature_enabled, false);
nh.param("runtime_pos_log_enable", runtime_pos_log, 0);
- nh.param("pcd_save_enable", pcd_save_en, 0);
- nh.param("mapping/extrinsic_est_en", extrinsic_est_en, 1);
+ nh.param("mapping/extrinsic_est_en", extrinsic_est_en, true);
+ nh.param("pcd_save/pcd_save_en", pcd_save_en, false);
+ nh.param("pcd_save/interval", pcd_save_interval, -1);
nh.param>("mapping/extrinsic_T", extrinT, vector());
nh.param>("mapping/extrinsic_R", extrinR, vector());
cout<<"p_pre->lidar_type "<lidar_type<