Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00019 #ifndef __VELODYNE_POINTCLOUD_POINT_TYPES_H
00020 #define __VELODYNE_POINTCLOUD_POINT_TYPES_H
00021
00022 #include <pcl/point_types.h>
00023
00024 namespace velodyne_pointcloud
00025 {
00027 struct PointXYZIR
00028 {
00029 PCL_ADD_POINT4D;
00030 float intensity;
00031 uint16_t ring;
00032 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00033 } EIGEN_ALIGN16;
00034
00035 };
00036
00037
00038 POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_pointcloud::PointXYZIR,
00039 (float, x, x)
00040 (float, y, y)
00041 (float, z, z)
00042 (float, intensity, intensity)
00043 (uint16_t, ring, ring))
00044
00045 #endif // __VELODYNE_POINTCLOUD_POINT_TYPES_H
00046