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

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