Go to the documentation of this file.00001 #include "pcl/pcl_base.h"
00002 #include "pcl/point_types.h"
00003 #include "jsk_pcl_ros/color_converter.h"
00004
00005 #include "pcl/kdtree/tree_types.h"
00006 #include "pcl/kdtree/kdtree.h"
00007 #include "pcl/kdtree/kdtree_flann.h"
00008 #include "pcl/kdtree/impl/kdtree_flann.hpp"
00009
00010 #include <boost/smart_ptr/make_shared.hpp>
00011
00012 int main (int argc, char** argv) {
00013 pcl::PointCloud<pcl::PointXYZRGB> p_rgb, p_rgb2;
00014 pcl::PointCloud<pcl::PointXYZHSV> p_hsv;
00015
00016 for(int r=0;r < 10; r++) {
00017 for(int g=0;g < 10; g++) {
00018 for(int b=0;b < 10; b++) {
00019 pcl::PointXYZRGB pt;
00020 pcl::RGBValue v;
00021 pt.x = r*25;
00022 pt.y = g*25;
00023 pt.z = b*25;
00024 v.Blue = r*25;
00025 v.Green = g*25;
00026 v.Red = b*25;
00027 pt.rgb = v.float_value;
00028 p_rgb.points.push_back(pt);
00029 }}}
00030
00031
00032
00033 p_rgb.is_dense = true;
00034 p_rgb.width = 1000;
00035 p_rgb.height = 1;
00036
00037 pcl::RGB2HSVConverter<pcl::PointXYZRGB, pcl::PointXYZHSV> rgb2hsv;
00038 pcl::HSV2RGBConverter<pcl::PointXYZHSV, pcl::PointXYZRGB> hsv2rgb;
00039
00040 pcl::KdTreeFLANN<pcl::PointXYZRGB>::Ptr tree
00041 = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZRGB> > ();
00042
00043 pcl::KdTreeFLANN<pcl::PointXYZHSV>::Ptr tree2
00044 = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZHSV> > ();
00045
00046 rgb2hsv.setSearchMethod (tree);
00047 rgb2hsv.setKSearch (50);
00048
00049 hsv2rgb.setSearchMethod (tree2);
00050 hsv2rgb.setKSearch (50);
00051
00052 rgb2hsv.setInputCloud(boost::make_shared<pcl::PointCloud<pcl::PointXYZRGB> > (p_rgb));
00053 rgb2hsv.compute(p_hsv);
00054
00055 hsv2rgb.setInputCloud(boost::make_shared<pcl::PointCloud<pcl::PointXYZHSV> > (p_hsv));
00056 hsv2rgb.compute(p_rgb2);
00057
00058 for(int i = 0 ; i < 1000; i++ )
00059 {
00060 pcl::PointXYZRGB rgb_p= p_rgb.points[i];
00061 pcl::PointXYZRGB rgb2_p= p_rgb2.points[i];
00062 pcl::PointXYZHSV hsv_p= p_hsv.points[i];
00063
00064 pcl::RGBValue v, v2;
00065 v.float_value = rgb_p.rgb;
00066 v2.float_value = rgb2_p.rgb;
00067
00068 std::cout << "[" << (int)v.Red << ", " << (int)v.Green << ", " << (int)v.Blue << "] -> "
00069 << "[" << hsv_p.hue << ", " << hsv_p.saturation << ", "
00070 << hsv_p.value << "] -> "
00071 << "[" << (int)v2.Red << ", "
00072 << (int)v2.Green << ", "
00073 << (int)v2.Blue << "]"
00074 << std::endl;
00075 }
00076 }