fix velodyne msg converting error

This commit is contained in:
haebum
2021-07-07 15:12:16 +09:00
committed by Cris.Wei
parent fd91caf212
commit 6dce4da6f9
2 changed files with 7 additions and 7 deletions

View File

@@ -282,7 +282,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg)
float yaw_last[MAX_LINE_NUM]={0.0}; // yaw of last scan point
float time_last[MAX_LINE_NUM]={0.0}; // last offset time
if (pl_orig.points[plsize - 1].t > 0)
if (pl_orig.points[plsize - 1].time > 0)
{
given_offset_time = true;
}
@@ -323,7 +323,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg)
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].t / 1000.0; // units: ms
added_pt.curvature = pl_orig.points[i].time / 1000.0; // units: ms
if (!given_offset_time)
{
@@ -392,7 +392,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg)
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].t / 1000.0;
added_pt.curvature = pl_orig.points[i].time / 1000.0;
if (!given_offset_time)
{
@@ -920,4 +920,4 @@ bool Preprocess::edge_jump_judge(const PointCloudXYZI &pl, vector<orgtype> &type
}
return true;
}
}