organize_pointcloud_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/o2r 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 
35 
38 
39 #include <pcl/common/centroid.h>
40 
41 namespace jsk_pcl_ros
42 {
43  void OrganizePointCloud::extract(const sensor_msgs::PointCloud2ConstPtr &input)
44  {
45  // skip empty cloud
46  ROS_INFO_STREAM("received input clouds, convert range image, resolution: " << angular_resolution << ", width(deg): " << angle_width << ", height(deg):" << angle_height << ", min_points:" << min_points);
47 
48  if ( input->width < min_points ) return;
49 
50  pcl::PointCloud<pcl::PointXYZ> pointCloud;
51  pcl::fromROSMsg(*input, pointCloud);
52 
53  // We now want to create a range image from the above point cloud, with a 1deg angular resolution
54  float angularResolution = (float) (angular_resolution * (M_PI/180.0f)); // 1.0 degree in radians
55  float maxAngleWidth = (float) (angle_width * (M_PI/180.0f)); // 120.0 degree in radians
56  float maxAngleHeight = (float) (angle_height * (M_PI/180.0f)); // 90.0 degree in radians
57  Eigen::Affine3f sensorPose = (Eigen::Affine3f)Eigen::Translation3f(0.0f, 0.0f, 0.0f);
58  pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;
59  float noiseLevel=0.00;
60  float minRange = 0.0f;
61  int borderSize = 1;
62 
63  pcl::RangeImage rangeImage;
64  rangeImage.createFromPointCloud(pointCloud, angularResolution, maxAngleWidth, maxAngleHeight,
65  sensorPose, coordinate_frame, noiseLevel, minRange, borderSize);
66  ROS_INFO_STREAM("input image size " << input->width << " x " << input->height << "(=" << input->width * input->height << ")");
67  ROS_INFO_STREAM("output image size " << rangeImage.width << " x " << rangeImage.height << "(=" << rangeImage.width * rangeImage.height << ")");
68  ROS_DEBUG_STREAM(rangeImage);
69 
70  sensor_msgs::PointCloud2 out;
71  pcl::toROSMsg(rangeImage, out);
72  out.header = input->header;
73  pub_.publish(out);
74  }
75 
77  {
78  ConnectionBasedNodelet::onInit();
79 
80  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
81  pnh_->param<double>("angular_resolution", angular_resolution, 1.0);
82  pnh_->param<double>("angle_width", angle_width, 120.0);
83  pnh_->param<double>("angle_height", angle_height, 90.0);
84  pnh_->param<int>("min_points", min_points, 1000);
86  }
87 
89  {
90  sub_ = pnh_->subscribe("input", 1, &OrganizePointCloud::extract, this);
91  }
92 
94  {
95  sub_.shutdown();
96  }
97 }
98 
100 
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
float
#define M_PI
virtual void extract(const sensor_msgs::PointCloud2ConstPtr &input)
boost::shared_ptr< ros::NodeHandle > pnh_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::OrganizePointCloud, nodelet::Nodelet)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)


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