heightmap_to_pointcloud_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
37 
40 #include <cv_bridge/cv_bridge.h>
42 #include <pcl/point_cloud.h>
43 #include <pcl/point_types.h>
44 
45 namespace jsk_pcl_ros
46 {
48  {
49  DiagnosticNodelet::onInit();
50  pub_config_ = pnh_->advertise<jsk_recognition_msgs::HeightmapConfig>(
51  "output/config", 1);
52  sub_config_ = pnh_->subscribe(
53  getHeightmapConfigTopic(pnh_->resolveName("input")), 1,
55  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
57  }
58 
60  {
61  sub_ = pnh_->subscribe("input", 1, &HeightmapToPointCloud::convert, this);
62  }
63 
65  {
66  sub_.shutdown();
67  }
68 
70  const jsk_recognition_msgs::HeightmapConfig::ConstPtr& msg)
71  {
72  boost::mutex::scoped_lock lock(mutex_);
73  config_msg_ = msg;
74  min_x_ = msg->min_x;
75  max_x_ = msg->max_x;
76  min_y_ = msg->min_y;
77  max_y_ = msg->max_y;
78  pub_config_.publish(msg);
79  }
80 
81  void HeightmapToPointCloud::convert(const sensor_msgs::Image::ConstPtr& msg)
82  {
83  boost::mutex::scoped_lock lock(mutex_);
84  if (!config_msg_) {
85  NODELET_ERROR("no ~input/config is yet available");
86  return;
87  }
88 
89  cv::Mat float_image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_32FC2)->image;
90  pcl::PointCloud<HeightMapPointType > cloud;
91 
92  bool keep_organized;
93  pnh_->param("keep_organized", keep_organized, false);
94  if (keep_organized) {
96  }
97  else {
98  convertHeightMapToPCL(float_image, cloud, max_x_, min_x_, max_y_, min_y_);
99  }
100 
101  sensor_msgs::PointCloud2 ros_cloud;
102  pcl::toROSMsg(cloud, ros_cloud);
103  ros_cloud.header = msg->header;
104  pub_.publish(ros_cloud);
105  }
106 }
107 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
jsk_recognition_msgs::HeightmapConfig::ConstPtr config_msg_
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
std::string getHeightmapConfigTopic(const std::string &base_topic)
virtual void convert(const sensor_msgs::Image::ConstPtr &msg)
void convertHeightMapToPCLOrganize(const cv::Mat &float_image, pcl::PointCloud< HeightMapPointType > &cloud, float max_x_, float min_x_, float max_y_, float min_y_)
boost::shared_ptr< ros::NodeHandle > pnh_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::HeightmapToPointCloud, nodelet::Nodelet)
virtual void configCallback(const jsk_recognition_msgs::HeightmapConfig::ConstPtr &msg)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
void convertHeightMapToPCL(const cv::Mat &float_image, pcl::PointCloud< HeightMapPointType > &cloud, float max_x_, float min_x_, float max_y_, float min_y_)
const std::string TYPE_32FC2
cloud


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