hsv_listener.cpp
Go to the documentation of this file.
1 #include "pcl/pcl_base.h"
3 #include "jsk_pcl_ros/color_converter.h"
4 
5 #include <ros/ros.h>
6 #include <sensor_msgs/PointCloud2.h>
7 
8 void callback(const sensor_msgs::PointCloud2::ConstPtr& msg)
9 {
10  pcl::PointCloud<pcl::PointHSV> cloud;
11  pcl::fromROSMsg(*msg, cloud);
12  for (size_t i = 0; i < cloud.points.size(); i++)
13  {
14  pcl::PointHSV point = cloud.points[i];
15  std::cout << "h: " << point.hue << "s: " << point.saturation
16  << "v: " << point.value << std::endl;
17  }
18 }
19 
20 int main(int argc, char** argv)
21 {
22  ros::init(argc, argv, "hoge");
24 
25  ros::Subscriber sub = n.subscribe("input", 1, callback);
26  ros::spin();
27  return 0;
28 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
GLfloat n[6][3]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ROSCPP_DECL void spin(Spinner &spinner)
void callback(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: hsv_listener.cpp:8
int main(int argc, char **argv)
cloud


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46