Go to the documentation of this file.00001
00008 #ifndef UCL_DRONE_POINTXYZRGBSIFT_H
00009 #define UCL_DRONE_POINTXYZRGBSIFT_H
00010 #define PCL_NO_PRECOMPILE
00011
00012 #include <ucl_drone/ucl_drone.h>
00013
00014 #include <pcl/point_types.h>
00015
00016 namespace pcl
00017 {
00018 struct PointXYZRGBSIFT
00019 {
00020 PCL_ADD_POINT4D;
00021
00022 PCL_ADD_RGB;
00023 float descriptor[DESCRIPTOR_SIZE];
00024 int view_count;
00025 int keyframe_ID;
00026
00027 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00028 } EIGEN_ALIGN16;
00029 }
00030
00031 POINT_CLOUD_REGISTER_POINT_STRUCT(pcl::PointXYZRGBSIFT,
00032
00033
00034 (float, x, x)(float, y, y)(float, z, z)(float, rgb, rgb)(
00035 float[DESCRIPTOR_SIZE], descriptor,
00036 descriptor)(int, view_count, view_count)(int, keyframe_ID,
00037 keyframe_ID))
00038
00039 namespace pcl
00040 {
00041 struct PointUVSIFT
00042 {
00043 float u;
00044 float v;
00045 float descriptor[DESCRIPTOR_SIZE];
00046
00047 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00048 } EIGEN_ALIGN16;
00049 }
00050
00051 POINT_CLOUD_REGISTER_POINT_STRUCT(pcl::PointUVSIFT,
00052
00053 (float, u, u)(float, v, v)(float[DESCRIPTOR_SIZE], descriptor,
00054 descriptor))
00055
00056 #endif