Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 #ifndef POINT_TYPES_H_
00009 #define POINT_TYPES_H_
00010
00011
00012 struct PointXYZRGBLabel
00013 {
00014 PCL_ADD_POINT4D;
00015 union
00016 {
00017 union
00018 {
00019 struct
00020 {
00021 uint8_t b;
00022 uint8_t g;
00023 uint8_t r;
00024 uint8_t _unused;
00025 };
00026 float rgb;
00027 };
00028 uint32_t rgba;
00029 };
00030 uint32_t label;
00031 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00032 } EIGEN_ALIGN16;
00033
00034 POINT_CLOUD_REGISTER_POINT_STRUCT(
00035 PointXYZRGBLabel,
00036 (float, x, x)
00037 (float, y, y)
00038 (float, z, z)
00039 (float, rgb, rgb)
00040 (uint32_t, label, label));
00041
00042
00043 struct PointXYZLabel
00044 {
00045 PCL_ADD_POINT4D;
00046 uint32_t label;
00047 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00048 } EIGEN_ALIGN16;
00049
00050 POINT_CLOUD_REGISTER_POINT_STRUCT(
00051 PointXYZLabel,
00052 (float, x, x)
00053 (float, y, y)
00054 (float, z, z)
00055 (uint32_t, label, label));
00056
00057
00058 struct PointXYZILabel
00059 {
00060 PCL_ADD_POINT4D;
00061 uint32_t intensity;
00062 uint32_t label;
00063 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00064 } EIGEN_ALIGN16;
00065
00066 POINT_CLOUD_REGISTER_POINT_STRUCT(
00067 PointXYZILabel,
00068 (float, x, x)
00069 (float, y, y)
00070 (float, z, z)
00071 (uint32_t, intensity, intensity)
00072 (uint32_t, label, label));
00073
00074 #endif