pointcloud_xyzrgb_to_xyz_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #define BOOST_PARAMETER_MAX_ARITY 7
36 
38 
40 
41 namespace jsk_pcl_ros_utils
42 {
43 
45 {
46  DiagnosticNodelet::onInit();
47  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
49 }
50 
52 {
53  sub_ = pnh_->subscribe("input", 1, &PointCloudXYZRGBToXYZ::convert, this);
54 }
55 
57 {
58  sub_.shutdown();
59 }
60 
61 void PointCloudXYZRGBToXYZ::convert(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
62 {
63  vital_checker_->poke();
64  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_xyzrgb(new pcl::PointCloud<pcl::PointXYZRGB>);
65  pcl::fromROSMsg(*cloud_msg, *cloud_xyzrgb);
66 
67  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz(new pcl::PointCloud<pcl::PointXYZ>);
68  cloud_xyz->points.resize(cloud_xyzrgb->points.size());
69  cloud_xyz->is_dense = cloud_xyzrgb->is_dense;
70  cloud_xyz->width = cloud_xyzrgb->width;
71  cloud_xyz->height = cloud_xyzrgb->height;
72  for (size_t i = 0; i < cloud_xyzrgb->points.size(); i++) {
73  pcl::PointXYZ p;
74  p.x = cloud_xyzrgb->points[i].x;
75  p.y = cloud_xyzrgb->points[i].y;
76  p.z = cloud_xyzrgb->points[i].z;
77  cloud_xyz->points[i] = p;
78  }
79  sensor_msgs::PointCloud2 out_cloud_msg;
80  pcl::toROSMsg(*cloud_xyz, out_cloud_msg);
81  out_cloud_msg.header = cloud_msg->header;
82  pub_.publish(out_cloud_msg);
83 }
84 
85 } // namespace jsk_pcl_ros_utils
86 
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PointCloudXYZRGBToXYZ, nodelet::Nodelet)
boost::shared_ptr< ros::NodeHandle > pnh_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
p
virtual void convert(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15