cloud_on_plane_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
40 
41 namespace jsk_pcl_ros_utils
42 {
44  {
45  DiagnosticNodelet::onInit();
46  pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
47  pnh_->param("approximate_sync", approximate_sync_, false);
48  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49  dynamic_reconfigure::Server<Config>::CallbackType f =
50  boost::bind (
52  srv_->setCallback (f);
53 
54  pub_ = advertise<jsk_recognition_msgs::BoolStamped>(*pnh_, "output", 1);
55 
56  onInitPostProcess();
57  }
58 
60  // message_filters::Synchronizer needs to be called reset
61  // before message_filters::Subscriber is freed.
62  // Calling reset fixes the following error on shutdown of the nodelet:
63  // terminate called after throwing an instance of
64  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
65  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
66  // Also see https://github.com/ros/ros_comm/issues/720 .
67  sync_.reset();
68  async_.reset();
69  }
70 
72  {
73  sub_cloud_.subscribe(*pnh_, "input", 1);
74  sub_polygon_.subscribe(*pnh_, "input/polygon", 1);
75  if (approximate_sync_) {
76  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> > (100);
77  async_->connectInput(sub_cloud_, sub_polygon_);
78  async_->registerCallback(boost::bind(&CloudOnPlane::predicate, this, _1, _2));
79  } else {
80  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> > (100);
81  sync_->connectInput(sub_cloud_, sub_polygon_);
82  sync_->registerCallback(boost::bind(&CloudOnPlane::predicate, this, _1, _2));
83  }
84  }
85 
87  {
90  }
91 
92  void CloudOnPlane::configCallback(Config& config, uint32_t level)
93  {
94  boost::mutex::scoped_lock lock(mutex_);
95  distance_thr_ = config.distance_thr;
96  buf_size_ = config.buf_size;
98  }
99 
100  void CloudOnPlane::predicate(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
101  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg)
102  {
103  boost::mutex::scoped_lock lock(mutex_);
104  vital_checker_->poke();
105  // check header
106  if (!jsk_recognition_utils::isSameFrameId(*cloud_msg, *polygon_msg)) {
107  NODELET_ERROR("frame_id does not match: cloud: %s, polygon: %s",
108  cloud_msg->header.frame_id.c_str(), polygon_msg->header.frame_id.c_str());
109  return;
110  }
111  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
112  pcl::fromROSMsg(*cloud_msg, *cloud);
113  // convert jsk_recognition_msgs::PolygonArray to jsk_recognition_utils::Polygon
114  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> polygons;
115  for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
116  polygons.push_back(jsk_recognition_utils::ConvexPolygon::fromROSMsgPtr(polygon_msg->polygons[i].polygon));
117  }
118 
119  for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
121  for (size_t j = 0; j < cloud->points.size(); j++) {
122  Eigen::Vector3f p = cloud->points[j].getVector3fMap();
123  if (poly->distanceSmallerThan(p, distance_thr_)) {
124  buffer_->addValue(false);
125  publishPredicate(cloud_msg->header, !buffer_->isAllTrueFilled());
126  return;
127  }
128  }
129  }
130  buffer_->addValue(true);
131  publishPredicate(cloud_msg->header, !buffer_->isAllTrueFilled());
132  }
133 
134  void CloudOnPlane::publishPredicate(const std_msgs::Header& header,
135  const bool v)
136  {
137  jsk_recognition_msgs::BoolStamped bool_stamped;
138  bool_stamped.header = header;
139  bool_stamped.data = v;
140  pub_.publish(bool_stamped);
141  }
142 }
143 
146 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
polygons
polygons
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_pcl_ros_utils::CloudOnPlane::buf_size_
int buf_size_
Definition: cloud_on_plane.h:152
_2
boost::arg< 2 > _2
boost::shared_ptr< ConvexPolygon >
jsk_pcl_ros_utils::CloudOnPlane::distance_thr_
double distance_thr_
Definition: cloud_on_plane.h:151
i
int i
jsk_recognition_utils::isSameFrameId
bool isSameFrameId(const std::string &a, const std::string &b)
p
p
pcl_ros_util.h
jsk_recognition_utils::SeriesedBoolean
lock
lock
jsk_pcl_ros_utils::CloudOnPlane::Config
CloudOnPlaneConfig Config
Definition: cloud_on_plane.h:124
jsk_pcl_ros_utils::CloudOnPlane::predicate
virtual void predicate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg)
Definition: cloud_on_plane_nodelet.cpp:100
jsk_pcl_ros_utils::CloudOnPlane::subscribe
virtual void subscribe()
Definition: cloud_on_plane_nodelet.cpp:71
jsk_pcl_ros_utils::CloudOnPlane::~CloudOnPlane
virtual ~CloudOnPlane()
Definition: cloud_on_plane_nodelet.cpp:59
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros_utils::CloudOnPlane::publishPredicate
virtual void publishPredicate(const std_msgs::Header &header, const bool v)
Definition: cloud_on_plane_nodelet.cpp:134
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
sample_camera_info_and_pointcloud_publisher.cloud
cloud
Definition: sample_camera_info_and_pointcloud_publisher.py:30
jsk_pcl_ros_utils::CloudOnPlane::unsubscribe
virtual void unsubscribe()
Definition: cloud_on_plane_nodelet.cpp:86
jsk_pcl_ros_utils::CloudOnPlane::onInit
virtual void onInit()
Definition: cloud_on_plane_nodelet.cpp:43
jsk_pcl_ros_utils::CloudOnPlane::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: cloud_on_plane.h:149
class_list_macros.h
jsk_pcl_ros_utils::CloudOnPlane::mutex_
boost::mutex mutex_
Definition: cloud_on_plane.h:144
jsk_pcl_ros_utils::CloudOnPlane::sub_polygon_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
Definition: cloud_on_plane.h:147
jsk_pcl_ros_utils::CloudOnPlane::approximate_sync_
bool approximate_sync_
Definition: cloud_on_plane.h:150
jsk_pcl_ros_utils::CloudOnPlane::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: cloud_on_plane.h:148
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::CloudOnPlane, nodelet::Nodelet)
jsk_pcl_ros_utils::CloudOnPlane
Definition: cloud_on_plane.h:88
_1
boost::arg< 1 > _1
jsk_pcl_ros_utils::CloudOnPlane::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: cloud_on_plane.h:145
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros_utils::CloudOnPlane::buffer_
jsk_recognition_utils::SeriesedBoolean::Ptr buffer_
Definition: cloud_on_plane.h:153
f
f
nodelet::Nodelet
jsk_pcl_ros_utils::CloudOnPlane::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: cloud_on_plane.h:146
jsk_pcl_ros_utils::CloudOnPlane::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: cloud_on_plane_nodelet.cpp:92
header
header
config
config
cloud_on_plane.h
jsk_recognition_utils::ConvexPolygon::fromROSMsgPtr
static ConvexPolygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
jsk_pcl_ros_utils::CloudOnPlane::pub_
ros::Publisher pub_
Definition: cloud_on_plane.h:143


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