hsv_listener.cpp
Go to the documentation of this file.
00001 #include "pcl/pcl_base.h"
00002 #include "jsk_pcl_ros/point_types.h"
00003 #include "jsk_pcl_ros/color_converter.h"
00004 
00005 #include <ros/ros.h>
00006 #include <sensor_msgs/PointCloud2.h>
00007 
00008 void callback(const sensor_msgs::PointCloud2::ConstPtr& msg)
00009 {
00010     pcl::PointCloud<pcl::PointHSV> cloud;
00011     pcl::fromROSMsg(*msg, cloud);
00012     for (size_t i = 0; i < cloud.points.size(); i++)
00013     {
00014         pcl::PointHSV point = cloud.points[i];
00015         std::cout << "h: " << point.hue << "s: " << point.saturation
00016                   << "v: " << point.value << std::endl;
00017     }
00018 }
00019 
00020 int main(int argc, char** argv)
00021 {
00022     ros::init(argc, argv, "hoge");
00023     ros::NodeHandle n;
00024 
00025     ros::Subscriber sub = n.subscribe("input", 1, callback);
00026     ros::spin();
00027     return 0;
00028 }


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:43