From 45aa82e4d6081bf04a8f5177b81e4f083d6899ea Mon Sep 17 00:00:00 2001 From: xw Date: Wed, 22 Sep 2021 22:58:38 -0400 Subject: [PATCH] add the scan rate parameter --- config/velodyne.yaml | 3 ++- rviz_cfg/loam_livox.rviz | 12 ++++++------ src/laserMapping.cpp | 1 + src/preprocess.cpp | 3 ++- src/preprocess.h | 2 +- 5 files changed, 12 insertions(+), 9 deletions(-) diff --git a/config/velodyne.yaml b/config/velodyne.yaml index 006ed96..4a8eed3 100644 --- a/config/velodyne.yaml +++ b/config/velodyne.yaml @@ -6,6 +6,7 @@ common: preprocess: lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, scan_line: 32 + scan_rate: 10 # only need to be set for velodyne, unit: Hz, blind: 4 mapping: @@ -15,7 +16,7 @@ mapping: b_gyr_cov: 0.0001 fov_degree: 180 det_range: 100.0 - extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic + extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic, extrinsic_T: [ 0, 0, 0.28] extrinsic_R: [ 1, 0, 0, 0, 1, 0, diff --git a/rviz_cfg/loam_livox.rviz b/rviz_cfg/loam_livox.rviz index 1553428..4dda6b6 100644 --- a/rviz_cfg/loam_livox.rviz +++ b/rviz_cfg/loam_livox.rviz @@ -85,7 +85,7 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 150 + Max Intensity: 159 Min Color: 238; 238; 236 Min Intensity: 0 Name: surround @@ -110,12 +110,12 @@ Visualization Manager: Channel Name: intensity Class: rviz/PointCloud2 Color: 255; 255; 255 - Color Transformer: AxisColor + Color Transformer: Intensity Decay Time: 1000 Enabled: true Invert Rainbow: true Max Color: 255; 255; 255 - Max Intensity: 0 + Max Intensity: 159 Min Color: 0; 0; 0 Min Intensity: 0 Name: currPoints @@ -348,11 +348,11 @@ Visualization Manager: Saved: ~ Window Geometry: Displays: - collapsed: true + collapsed: false Height: 1383 - Hide Left Dock: true + Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd0000000400000000000001c8000004b5fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d000004b5000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000004b7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000061f00000052fc0100000002fb0000000800540069006d006501000000000000061f000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000061f000004b500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000001c8000004b5fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000004b5000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c700000000000000000000000100000152000004b7fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000004b7000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000061f00000052fc0100000002fb0000000800540069006d006501000000000000061f000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000451000004b500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: diff --git a/src/laserMapping.cpp b/src/laserMapping.cpp index 43e8f24..1404243 100644 --- a/src/laserMapping.cpp +++ b/src/laserMapping.cpp @@ -773,6 +773,7 @@ int main(int argc, char** argv) nh.param("preprocess/blind", p_pre->blind, 0.01); nh.param("preprocess/lidar_type", p_pre->lidar_type, AVIA); nh.param("preprocess/scan_line", p_pre->N_SCANS, 16); + nh.param("preprocess/scan_rate", p_pre->SCAN_RATE, 10); nh.param("point_filter_num", p_pre->point_filter_num, 2); nh.param("feature_extract_enable", p_pre->feature_enabled, false); nh.param("runtime_pos_log_enable", runtime_pos_log, 0); diff --git a/src/preprocess.cpp b/src/preprocess.cpp index f12eb57..3f0cb62 100644 --- a/src/preprocess.cpp +++ b/src/preprocess.cpp @@ -8,6 +8,7 @@ Preprocess::Preprocess() { inf_bound = 10; N_SCANS = 6; + SCAN_RATE = 10; group_size = 8; disA = 0.01; disA = 0.1; // B? @@ -269,7 +270,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) pl_surf.reserve(plsize); /*** These variables only works when no point timestamps given ***/ - double omega_l=3.61; // scan angular velocity + double omega_l = 0.361 * SCAN_RATE; // scan angular velocity std::vector is_first(N_SCANS,true); std::vector yaw_fp(N_SCANS, 0.0); // yaw of first scan point std::vector yaw_last(N_SCANS, 0.0); // yaw of last scan point diff --git a/src/preprocess.h b/src/preprocess.h index 28303be..8fb058b 100644 --- a/src/preprocess.h +++ b/src/preprocess.h @@ -94,7 +94,7 @@ class Preprocess PointCloudXYZI pl_full, pl_corn, pl_surf; PointCloudXYZI pl_buff[128]; //maximum 128 line lidar vector typess[128]; //maximum 128 line lidar - int lidar_type, point_filter_num, N_SCANS;; + int lidar_type, point_filter_num, N_SCANS, SCAN_RATE; double blind; bool feature_enabled, given_offset_time; ros::Publisher pub_full, pub_surf, pub_corn;