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/or 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  onInitPostProcess();
89  }
90 
92  // message_filters::Synchronizer needs to be called reset
93  // before message_filters::Subscriber is freed.
94  // Calling reset fixes the following error on shutdown of the nodelet:
95  // terminate called after throwing an instance of
96  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
97  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
98  // Also see https://github.com/ros/ros_comm/issues/720 .
99  sync_.reset();
100  async_.reset();
101  }
102 
104  {
105  sub_xyz_.subscribe(*pnh_, "input", 1);
106  sub_normal_.subscribe(*pnh_, "normal", 1);
107  if (use_async_) {
108  async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(maximum_queue_size_);
109  async_->connectInput(sub_xyz_, sub_normal_);
110  async_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, _1, _2));
111  }
112  else {
113  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(maximum_queue_size_);
114  sync_->connectInput(sub_xyz_, sub_normal_);
115  sync_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, _1, _2));
116  }
117  }
118 
120  {
123  }
124 
125 }
126 
128 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_pcl_ros_utils::NormalConcatenater::use_async_
bool use_async_
Definition: normal_concatenater.h:135
_2
boost::arg< 2 > _2
jsk_pcl_ros_utils::NormalConcatenater::pub_
ros::Publisher pub_
Definition: normal_concatenater.h:126
i
int i
jsk_pcl_ros_utils::NormalConcatenater::subscribe
virtual void subscribe()
Definition: normal_concatenater_nodelet.cpp:135
jsk_pcl_ros_utils::NormalConcatenater::unsubscribe
virtual void unsubscribe()
Definition: normal_concatenater_nodelet.cpp:151
jsk_pcl_ros_utils::NormalConcatenater::sub_normal_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
Definition: normal_concatenater.h:131
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros_utils::NormalConcatenater
Definition: normal_concatenater.h:87
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros_utils::NormalConcatenater::~NormalConcatenater
virtual ~NormalConcatenater()
Definition: normal_concatenater_nodelet.cpp:123
message_filters::Subscriber::unsubscribe
void unsubscribe()
class_list_macros.h
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::NormalConcatenater, nodelet::Nodelet)
_1
boost::arg< 1 > _1
jsk_pcl_ros_utils::NormalConcatenater::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: normal_concatenater.h:128
point
std::chrono::system_clock::time_point point
jsk_pcl_ros_utils::NormalConcatenater::maximum_queue_size_
int maximum_queue_size_
Definition: normal_concatenater.h:127
jsk_pcl_ros_utils::NormalConcatenater::async_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
Definition: normal_concatenater.h:129
jsk_pcl_ros_utils::NormalConcatenater::concatenate
virtual void concatenate(const sensor_msgs::PointCloud2::ConstPtr &xyz, const sensor_msgs::PointCloud2::ConstPtr &normal)
Definition: normal_concatenater_nodelet.cpp:73
message_filters::Subscriber::subscribe
void subscribe()
normal_concatenater.h
nodelet::Nodelet
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros_utils::NormalConcatenater::onInit
virtual void onInit()
Definition: normal_concatenater_nodelet.cpp:111
jsk_pcl_ros_utils::NormalConcatenater::sub_xyz_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_xyz_
Definition: normal_concatenater.h:130


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43