fix velodyne msg converting error

main
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;
}
}

View File

@ -37,7 +37,7 @@ namespace velodyne_ros {
struct EIGEN_ALIGN16 Point {
PCL_ADD_POINT4D;
float intensity;
uint32_t t;
float time;
uint16_t ring;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
@ -47,7 +47,7 @@ POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_ros::Point,
(float, y, y)
(float, z, z)
(float, intensity, intensity)
(uint32_t, t, t)
(float, time, time)
(uint16_t, ring, ring)
)
@ -119,4 +119,4 @@ class Preprocess
double edgea, edgeb;
double smallp_intersect, smallp_ratio;
double vx, vy, vz;
};
};