border_estimator_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, 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
38 #include <pcl/range_image/range_image_planar.h>
39 #include <pcl/range_image/range_image_spherical.h>
41 #include <cv_bridge/cv_bridge.h>
43 
44 namespace jsk_pcl_ros
45 {
47  {
48  ConnectionBasedNodelet::onInit();
49  // planar or spherical
50  pnh_->param("model_type", model_type_, std::string("planar"));
51  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
52  typename dynamic_reconfigure::Server<Config>::CallbackType f =
53  boost::bind (&BorderEstimator::configCallback, this, _1, _2);
54  srv_->setCallback (f);
55 
56  pub_border_ = advertise<PCLIndicesMsg>(*pnh_, "output_border_indices", 1);
57  pub_veil_ = advertise<PCLIndicesMsg>(*pnh_, "output_veil_indices", 1);
58  pub_shadow_ = advertise<PCLIndicesMsg>(*pnh_, "output_shadow_indices", 1);
59  pub_range_image_ = advertise<sensor_msgs::Image>(
60  *pnh_, "output_range_image", 1);
61  pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
62  *pnh_, "output_cloud", 1);
63 
65  }
66 
68  {
69  if (model_type_ == "planar") {
70  sub_point_.subscribe(*pnh_, "input", 1);
71  sub_camera_info_.subscribe(*pnh_, "input_camera_info", 1);
72  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
73  sync_->connectInput(sub_point_, sub_camera_info_);
74  sync_->registerCallback(boost::bind(&BorderEstimator::estimate, this, _1, _2));
75  }
76  else if (model_type_ == "laser") {
77  sub_ = pnh_->subscribe("input", 1, &BorderEstimator::estimate, this);
78  }
79  }
80 
82  {
83  if (model_type_ == "planar") {
86  }
87  else if (model_type_ == "laser") {
88  sub_.shutdown();
89  }
90  }
91 
94  const pcl::PointIndices& inlier,
95  const std_msgs::Header& header)
96  {
98  msg.header = header;
99  msg.indices = inlier.indices;
100  pub.publish(msg);
101  }
102 
104  const sensor_msgs::PointCloud2::ConstPtr& msg)
105  {
106  boost::mutex::scoped_lock lock(mutex_);
107  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
108  pcl::fromROSMsg(*msg, *cloud);
109  pcl::RangeImage range_image;
110  if (model_type_ == "sphere") {
111  range_image = pcl::RangeImageSpherical();
112  }
113  range_image.createFromPointCloud(
114  *cloud,
117  Eigen::Affine3f::Identity(),
118  pcl::RangeImage::CAMERA_FRAME,
119  noise_level_,
120  min_range_,
121  border_size_);
122  range_image.setUnseenToMaxRange();
123  computeBorder(range_image, msg->header);
124  }
125 
127  const pcl::RangeImage& range_image,
128  const std_msgs::Header& header)
129  {
130  pcl::RangeImageBorderExtractor border_extractor (&range_image);
131  pcl::PointCloud<pcl::BorderDescription> border_descriptions;
132  border_extractor.compute (border_descriptions);
133  pcl::PointIndices border_indices, veil_indices, shadow_indices;
134  for (int y = 0; y < (int)range_image.height; ++y) {
135  for (int x = 0; x < (int)range_image.width; ++x) {
136  if (border_descriptions.points[y*range_image.width + x].traits[pcl::BORDER_TRAIT__OBSTACLE_BORDER]) {
137  border_indices.indices.push_back (y*range_image.width + x);
138  }
139  if (border_descriptions.points[y*range_image.width + x].traits[pcl::BORDER_TRAIT__VEIL_POINT]) {
140  veil_indices.indices.push_back (y*range_image.width + x);
141  }
142  if (border_descriptions.points[y*range_image.width + x].traits[pcl::BORDER_TRAIT__SHADOW_BORDER]) {
143  shadow_indices.indices.push_back (y*range_image.width + x);
144  }
145  }
146  }
147  publishCloud(pub_border_, border_indices, header);
148  publishCloud(pub_veil_, veil_indices, header);
149  publishCloud(pub_shadow_, shadow_indices, header);
150  cv::Mat image;
151  jsk_recognition_utils::rangeImageToCvMat(range_image, image);
153  cv_bridge::CvImage(header,
155  image).toImageMsg());
156  // publish pointcloud
157  sensor_msgs::PointCloud2 ros_cloud;
158  pcl::toROSMsg(range_image, ros_cloud);
159  ros_cloud.header = header;
160  pub_cloud_.publish(ros_cloud);
161  }
162 
164  const sensor_msgs::PointCloud2::ConstPtr& msg,
165  const sensor_msgs::CameraInfo::ConstPtr& info)
166  {
167  if (msg->height == 1) {
168  NODELET_ERROR("[BorderEstimator::estimate] pointcloud must be organized");
169  return;
170  }
171  pcl::RangeImagePlanar range_image;
172  pcl::PointCloud<pcl::PointXYZ> cloud;
173  pcl::fromROSMsg(*msg, cloud);
174  Eigen::Affine3f dummytrans = Eigen::Affine3f::Identity();
175  float fx = info->P[0];
176  float cx = info->P[2];
177  float tx = info->P[3];
178  float fy = info->P[5];
179  float cy = info->P[6];
180  range_image.createFromPointCloudWithFixedSize (cloud,
181  msg->width,
182  msg->height,
183  cx, cy,
184  fx, fy,
185  dummytrans);
186  range_image.setUnseenToMaxRange();
187  computeBorder(range_image, msg->header);
188  }
189 
190  void BorderEstimator::configCallback(Config &config, uint32_t level)
191  {
192  boost::mutex::scoped_lock lock(mutex_);
193  noise_level_ = config.noise_level;
194  min_range_ = config.min_range;
195  border_size_ = config.border_size;
196  angular_resolution_ = config.angular_resolution;
197  max_angle_height_ = config.max_angle_height;
198  max_angle_width_ = config.max_angle_width;
199  }
200 }
201 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::BorderEstimator, nodelet::Nodelet)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
BorderEstimatorConfig Config
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &caminfo)
virtual void configCallback(Config &config, uint32_t level)
void rangeImageToCvMat(const pcl::RangeImage &range_image, cv::Mat &mat)
virtual void publishCloud(ros::Publisher &pub, const pcl::PointIndices &inlier, const std_msgs::Header &header)
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual void computeBorder(const pcl::RangeImage &image, const std_msgs::Header &header)
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::CameraInfo > sub_camera_info_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pcl::PointIndices PCLIndicesMsg
cloud


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46