normal_concatenater_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ryohei Ueda and 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 
37 
38 namespace jsk_pcl_ros_utils
39 {
40 
41  void NormalConcatenater::concatenate(const sensor_msgs::PointCloud2::ConstPtr& xyz,
42  const sensor_msgs::PointCloud2::ConstPtr& normal)
43  {
44  if (xyz->width != normal->width || xyz->height != normal->height) {
45  NODELET_ERROR("~input and ~normal's width or height does not match");
46  NODELET_ERROR("xyz: width=%d, height=%d", xyz->width, xyz->height);
47  NODELET_ERROR("normal: width=%d, height=%d", normal->width, normal->height);
48  return;
49  }
50  pcl::PointCloud<pcl::PointXYZRGB> xyz_cloud;
51  pcl::PointCloud<pcl::Normal> normal_cloud;
52  pcl::PointCloud<pcl::PointXYZRGBNormal> concatenated_cloud;
53  pcl::fromROSMsg(*xyz, xyz_cloud);
54  pcl::fromROSMsg(*normal, normal_cloud);
55 
56  concatenated_cloud.points.resize(xyz_cloud.points.size());
57  concatenated_cloud.width = xyz_cloud.width;
58  concatenated_cloud.height = xyz_cloud.height;
59  concatenated_cloud.is_dense = xyz_cloud.is_dense;
60 
61  for (size_t i = 0; i < concatenated_cloud.points.size(); i++) {
62  pcl::PointXYZRGBNormal point;
63  point.x = xyz_cloud.points[i].x;
64  point.y = xyz_cloud.points[i].y;
65  point.z = xyz_cloud.points[i].z;
66  point.rgb = xyz_cloud.points[i].rgb;
67  point.normal_x = normal_cloud.points[i].normal_x;
68  point.normal_y = normal_cloud.points[i].normal_y;
69  point.normal_z = normal_cloud.points[i].normal_z;
70  point.curvature = normal_cloud.points[i].curvature;
71  concatenated_cloud.points[i] = point;
72  }
73  sensor_msgs::PointCloud2 output_cloud;
74  pcl::toROSMsg(concatenated_cloud, output_cloud);
75  output_cloud.header = xyz->header;
76  pub_.publish(output_cloud);
77  }
78 
80  {
81  ConnectionBasedNodelet::onInit();
82  pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
83  pnh_->param("use_async", use_async_, false);
84  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
85  if (!pnh_->getParam("max_queue_size", maximum_queue_size_)) {
86  maximum_queue_size_ = 100;
87  }
88  }
89 
91  {
92  sub_xyz_.subscribe(*pnh_, "input", 1);
93  sub_normal_.subscribe(*pnh_, "normal", 1);
94  if (use_async_) {
95  async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(maximum_queue_size_);
96  async_->connectInput(sub_xyz_, sub_normal_);
97  async_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, _1, _2));
98  }
99  else {
100  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(maximum_queue_size_);
101  sync_->connectInput(sub_xyz_, sub_normal_);
102  sync_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, _1, _2));
103  }
104  }
105 
107  {
110  }
111 
112 }
113 
115 
#define NODELET_ERROR(...)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::NormalConcatenater, nodelet::Nodelet)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_xyz_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
boost::shared_ptr< ros::NodeHandle > pnh_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
double x
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
virtual void concatenate(const sensor_msgs::PointCloud2::ConstPtr &xyz, const sensor_msgs::PointCloud2::ConstPtr &normal)


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