selected_cluster_publisher_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 #include <pcl/filters/extract_indices.h>
38 
40 
41 namespace jsk_pcl_ros
42 {
44  {
45  ConnectionBasedNodelet::onInit();
46  pnh_->param("keep_organized", keep_organized_, false);
47  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
48  onInitPostProcess();
49  }
50 
52  // message_filters::Synchronizer needs to be called reset
53  // before message_filters::Subscriber is freed.
54  // Calling reset fixes the following error on shutdown of the nodelet:
55  // terminate called after throwing an instance of
56  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
57  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
58  // Also see https://github.com/ros/ros_comm/issues/720 .
59  sync_.reset();
60  }
61 
63  {
64  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(300); // 100 is enough?
65  sub_input_.subscribe(*pnh_, "input", 1);
66  sub_indices_.subscribe(*pnh_, "indices", 1);
67  sub_index_.subscribe(*pnh_, "selected_index", 1);
68  sync_->connectInput(sub_input_, sub_indices_, sub_index_);
69  sync_->registerCallback(boost::bind(&SelectedClusterPublisher::extract, this, _1, _2, _3));
70  }
71 
73  {
77  }
78 
79  void SelectedClusterPublisher::extract(const sensor_msgs::PointCloud2::ConstPtr& input,
80  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
81  const jsk_recognition_msgs::Int32Stamped::ConstPtr& index)
82  {
83  if (indices->cluster_indices.size() <= index->data) {
84  NODELET_ERROR("the selected index %d is out of clusters array %lu",
85  index->data,
86  indices->cluster_indices.size());
87  return;
88  }
89  pcl::PointCloud<pcl::PointXYZRGB>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZRGB>());
90  pcl::fromROSMsg(*input, *input_cloud);
91  pcl::ExtractIndices<pcl::PointXYZRGB> extract;
92  pcl::PointIndices::Ptr pcl_indices (new pcl::PointIndices);
93  pcl_indices->indices = indices->cluster_indices[index->data].indices;
94  extract.setInputCloud(input_cloud);
95  extract.setIndices(pcl_indices);
96  pcl::PointCloud<pcl::PointXYZRGB>::Ptr extracted_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
97  if(keep_organized_){
98  extract.setKeepOrganized(true);
99  }
100  extract.filter(*extracted_cloud);
101  sensor_msgs::PointCloud2 ros_msg;
102  pcl::toROSMsg(*extracted_cloud, ros_msg);
103  ros_msg.header = input->header;
104  pub_.publish(ros_msg);
105  }
106 }
107 
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_pcl_ros::SelectedClusterPublisher::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: selected_cluster_publisher.h:121
jsk_pcl_ros::SelectedClusterPublisher::subscribe
virtual void subscribe()
Definition: selected_cluster_publisher_nodelet.cpp:94
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::SelectedClusterPublisher
Definition: selected_cluster_publisher.h:82
class_list_macros.h
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::SelectedClusterPublisher::unsubscribe
virtual void unsubscribe()
Definition: selected_cluster_publisher_nodelet.cpp:104
jsk_pcl_ros::SelectedClusterPublisher::sub_index_
message_filters::Subscriber< jsk_recognition_msgs::Int32Stamped > sub_index_
Definition: selected_cluster_publisher.h:123
jsk_pcl_ros::SelectedClusterPublisher::extract
virtual void extract(const sensor_msgs::PointCloud2::ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices, const jsk_recognition_msgs::Int32Stamped::ConstPtr &index)
Definition: selected_cluster_publisher_nodelet.cpp:111
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::SelectedClusterPublisher, nodelet::Nodelet)
jsk_pcl_ros::SelectedClusterPublisher::onInit
virtual void onInit()
Definition: selected_cluster_publisher_nodelet.cpp:75
pcl_conversion_util.h
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros::SelectedClusterPublisher::~SelectedClusterPublisher
virtual ~SelectedClusterPublisher()
Definition: selected_cluster_publisher_nodelet.cpp:83
nodelet::Nodelet
jsk_pcl_ros::SelectedClusterPublisher::keep_organized_
bool keep_organized_
Definition: selected_cluster_publisher.h:134
jsk_pcl_ros::SelectedClusterPublisher::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: selected_cluster_publisher.h:124
jsk_pcl_ros::SelectedClusterPublisher::pub_
ros::Publisher pub_
Definition: selected_cluster_publisher.h:120
index
unsigned int index
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
selected_cluster_publisher.h
jsk_pcl_ros::SelectedClusterPublisher::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: selected_cluster_publisher.h:122
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45