pcl::PointCloud<robosense_ros::Point> pl_orig;
pcl::fromROSMsg(*msg, pl_orig);
int plsize = pl_orig.points.size();
cloud_out_.reserve(plsize);
/*** These variables only works when no point timestamps given ***/
double omega_l = 3.61; // scan angular velocity
std::vector<bool> is_first(num_scans_, true);
std::vector<double> yaw_fp(num_scans_, 0.0); // yaw of first scan point
std::vector<float> yaw_last(num_scans_, 0.0); // yaw of last scan point
std::vector<float> time_last(num_scans_, 0.0); // last offset time
/*****************************************************************/
if (pl_orig.points[plsize - 1].timestamp > 0) {
given_offset_time_ = true;
} else {
given_offset_time_ = false;
double yaw_first = atan2(pl_orig.points[0].y, pl_orig.points[0].x) * 57.29578;
double yaw_end = yaw_first;
int layer_first = pl_orig.points[0].ring;
for (uint i = plsize - 1; i > 0; i--) {
if (pl_orig.points[i].ring == layer_first) {
yaw_end = atan2(pl_orig.points[i].y, pl_orig.points[i].x) * 57.29578;
break;
}
}
}
for (int i = 0; i < plsize; i++) {
PointType added_pt;
added_pt.normal_x = 0;
added_pt.normal_y = 0;
added_pt.normal_z = 0;
added_pt.x = pl_orig.points[i].x;
added_pt.y = pl_orig.points[i].y;
added_pt.z = pl_orig.points[i].z;
added_pt.intensity = pl_orig.points[i].intensity;
added_pt.curvature =(pl_orig.points[i].timestamp - msg->header.stamp.toSec()) * 1000; // curvature unit: ms
if (!given_offset_time_) {
int layer = pl_orig.points[i].ring;
double yaw_angle = atan2(added_pt.y, added_pt.x) * 57.2957;
if (is_first[layer]) {
yaw_fp[layer] = yaw_angle;
is_first[layer] = false;
added_pt.curvature = 0.0;
yaw_last[layer] = yaw_angle;
time_last[layer] = added_pt.curvature;
continue;
}
// compute offset time
if (yaw_angle <= yaw_fp[layer]) {
added_pt.curvature = (yaw_fp[layer] - yaw_angle) / omega_l;
} else {
added_pt.curvature = (yaw_fp[layer] - yaw_angle + 360.0) / omega_l;
}
if (added_pt.curvature < time_last[layer]) added_pt.curvature += 360.0 / omega_l;
yaw_last[layer] = yaw_angle;
time_last[layer] = added_pt.curvature;
}
if (i % point_filter_num_ == 0) {
if (added_pt.x * added_pt.x + added_pt.y * added_pt.y + added_pt.z * added_pt.z > (blind_ * blind_)) {
cloud_out_.points.push_back(added_pt);
}
}
}
}
同时也修改了 velodyne_utbm.yaml
common:
lid_topic: "/rslidar_points"
imu_topic: "/imu/data"
time_sync_en: true # ONLY turn on when external time synchronization is really not possible
preprocess:
lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
scan_line: 32
blind: 4
time_scale: 1e-3 # 兼容不同数据集的时间单位
mapping:
acc_cov: 0.1
gyr_cov: 0.1
b_acc_cov: 0.0001
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_T: [ -0.5, 1.4, 1.5]
extrinsic_R: [ 1, 0, 0,
0, 1, 0,
0, 0, 1]
publish:
path_publish_en: false
scan_publish_en: true # false: close all the point cloud output
scan_effect_pub_en: true # true: publish the pointscloud of effect point
dense_publish_en: false # 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
path_save_en: true # 保存轨迹,用于精度计算和比较
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.
void PointCloudPreprocess::VelodyneHandler(const sensor_msgs::PointCloud2::ConstPtr &msg) { cloudout.clear(); cloudfull.clear();
}
同时也修改了 velodyne_utbm.yaml
common: lid_topic: "/rslidar_points" imu_topic: "/imu/data" time_sync_en: true # ONLY turn on when external time synchronization is really not possible
preprocess: lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, scan_line: 32 blind: 4 time_scale: 1e-3 # 兼容不同数据集的时间单位 mapping: acc_cov: 0.1 gyr_cov: 0.1 b_acc_cov: 0.0001 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_T: [ -0.5, 1.4, 1.5] extrinsic_R: [ 1, 0, 0, 0, 1, 0, 0, 0, 1] publish: path_publish_en: false scan_publish_en: true # false: close all the point cloud output scan_effect_pub_en: true # true: publish the pointscloud of effect point dense_publish_en: false # 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 path_save_en: true # 保存轨迹,用于精度计算和比较 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.
feature_extract_enable: false point_filter_num: 6 max_iteration: 3 filter_size_surf: 0.5 filter_size_map: 0.5 cube_side_length: 1000 ivox_grid_resolution: 0.5 # default=0.2 ivox_nearby_type: 18 # 6, 18, 26 esti_plane_threshold: 0.1 # default=0.1