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/o2r 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 (
51  &CloudOnPlane::configCallback, this, _1, _2);
52  srv_->setCallback (f);
53 
54  pub_ = advertise<jsk_recognition_msgs::BoolStamped>(*pnh_, "output", 1);
55 
57  }
58 
60  {
61  sub_cloud_.subscribe(*pnh_, "input", 1);
62  sub_polygon_.subscribe(*pnh_, "input/polygon", 1);
63  if (approximate_sync_) {
64  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> > (100);
65  async_->connectInput(sub_cloud_, sub_polygon_);
66  async_->registerCallback(boost::bind(&CloudOnPlane::predicate, this, _1, _2));
67  } else {
68  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> > (100);
69  sync_->connectInput(sub_cloud_, sub_polygon_);
70  sync_->registerCallback(boost::bind(&CloudOnPlane::predicate, this, _1, _2));
71  }
72  }
73 
75  {
78  }
79 
80  void CloudOnPlane::configCallback(Config& config, uint32_t level)
81  {
82  boost::mutex::scoped_lock lock(mutex_);
83  distance_thr_ = config.distance_thr;
84  buf_size_ = config.buf_size;
86  }
87 
88  void CloudOnPlane::predicate(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
89  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg)
90  {
91  boost::mutex::scoped_lock lock(mutex_);
92  vital_checker_->poke();
93  // check header
94  if (!jsk_recognition_utils::isSameFrameId(*cloud_msg, *polygon_msg)) {
95  NODELET_ERROR("frame_id does not match: cloud: %s, polygon: %s",
96  cloud_msg->header.frame_id.c_str(), polygon_msg->header.frame_id.c_str());
97  return;
98  }
99  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
100  pcl::fromROSMsg(*cloud_msg, *cloud);
101  // convert jsk_recognition_msgs::PolygonArray to jsk_recognition_utils::Polygon
102  std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> polygons;
103  for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
104  polygons.push_back(jsk_recognition_utils::ConvexPolygon::fromROSMsgPtr(polygon_msg->polygons[i].polygon));
105  }
106 
107  for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
109  for (size_t j = 0; j < cloud->points.size(); j++) {
110  Eigen::Vector3f p = cloud->points[j].getVector3fMap();
111  if (poly->distanceSmallerThan(p, distance_thr_)) {
112  buffer_->addValue(false);
113  publishPredicate(cloud_msg->header, !buffer_->isAllTrueFilled());
114  return;
115  }
116  }
117  }
118  buffer_->addValue(true);
119  publishPredicate(cloud_msg->header, !buffer_->isAllTrueFilled());
120  }
121 
122  void CloudOnPlane::publishPredicate(const std_msgs::Header& header,
123  const bool v)
124  {
125  jsk_recognition_msgs::BoolStamped bool_stamped;
126  bool_stamped.header = header;
127  bool_stamped.data = v;
128  pub_.publish(bool_stamped);
129  }
130 }
131 
134 
f
lock
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void predicate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
static ConvexPolygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
virtual void configCallback(Config &config, uint32_t level)
virtual void publishPredicate(const std_msgs::Header &header, const bool v)
jsk_recognition_utils::SeriesedBoolean::Ptr buffer_
boost::shared_ptr< ros::NodeHandle > pnh_
jsk_topic_tools::VitalChecker::Ptr vital_checker_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
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)
p
bool isSameFrameId(const std::string &a, const std::string &b)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::CloudOnPlane, nodelet::Nodelet)
polygons


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