heightmap_to_pointcloud_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 
00038 #include "jsk_pcl_ros/heightmap_to_pointcloud.h"
00039 #include <pcl_conversions/pcl_conversions.h>
00040 #include <cv_bridge/cv_bridge.h>
00041 #include <sensor_msgs/image_encodings.h>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 
00045 namespace jsk_pcl_ros
00046 {
00047   void HeightmapToPointCloud::onInit()
00048   {
00049     DiagnosticNodelet::onInit();
00050     pub_config_ = pnh_->advertise<jsk_recognition_msgs::HeightmapConfig>(
00051       "output/config", 1);
00052     sub_config_ = pnh_->subscribe(
00053       getHeightmapConfigTopic(pnh_->resolveName("input")), 1,
00054       &HeightmapToPointCloud::configCallback, this);
00055     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00056     onInitPostProcess();
00057   }
00058 
00059   void HeightmapToPointCloud::subscribe()
00060   {
00061     sub_ = pnh_->subscribe("input", 1, &HeightmapToPointCloud::convert, this);
00062   }
00063 
00064   void HeightmapToPointCloud::unsubscribe()
00065   {
00066     sub_.shutdown();
00067   }
00068 
00069   void HeightmapToPointCloud::configCallback(
00070     const jsk_recognition_msgs::HeightmapConfig::ConstPtr& msg)
00071   {
00072     boost::mutex::scoped_lock lock(mutex_);
00073     config_msg_ = msg;
00074     min_x_ = msg->min_x;
00075     max_x_ = msg->max_x;
00076     min_y_ = msg->min_y;
00077     max_y_ = msg->max_y;
00078     pub_config_.publish(msg);
00079   }
00080 
00081   void HeightmapToPointCloud::convert(const sensor_msgs::Image::ConstPtr& msg)
00082   {
00083     boost::mutex::scoped_lock lock(mutex_);
00084     if (!config_msg_) {
00085       NODELET_ERROR("no ~input/config is yet available");
00086       return;
00087     }
00088 
00089     cv::Mat float_image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_32FC2)->image;
00090     pcl::PointCloud<HeightMapPointType > cloud;
00091 
00092     bool keep_organized;
00093     pnh_->param("keep_organized", keep_organized, false);
00094     if (keep_organized) {
00095       convertHeightMapToPCLOrganize(float_image, cloud, max_x_, min_x_, max_y_, min_y_);
00096     }
00097     else {
00098       convertHeightMapToPCL(float_image, cloud, max_x_, min_x_, max_y_, min_y_);
00099     }
00100 
00101     sensor_msgs::PointCloud2 ros_cloud;
00102     pcl::toROSMsg(cloud, ros_cloud);
00103     ros_cloud.header = msg->header;
00104     pub_.publish(ros_cloud);
00105   }
00106 }
00107 
00108 #include <pluginlib/class_list_macros.h>
00109 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::HeightmapToPointCloud, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:43