heightmap_converter_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, 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 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/heightmap_converter.h"
00037 #include <pcl_conversions/pcl_conversions.h>
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <jsk_topic_tools/color_utils.h>
00041 
00042 namespace jsk_pcl_ros
00043 {
00044   void HeightmapConverter::onInit()
00045   {
00046     DiagnosticNodelet::onInit();
00047     pub_config_ = pnh_->advertise<jsk_recognition_msgs::HeightmapConfig>(
00048       "output/config", 1, true);
00049     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00050     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00051       boost::bind (&HeightmapConverter::configCallback, this, _1, _2);
00052     srv_->setCallback (f);
00053 
00054     pnh_->param("max_queue_size", max_queue_size_, 10);
00055     pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00056   }
00057   
00058   void HeightmapConverter::subscribe()
00059   {
00060     sub_ = pnh_->subscribe("input", max_queue_size_, &HeightmapConverter::convert, this);
00061   }
00062 
00063   void HeightmapConverter::unsubscribe()
00064   {
00065     sub_.shutdown();
00066   }
00067 
00068   void HeightmapConverter::convert(const sensor_msgs::PointCloud2::ConstPtr& msg)
00069   {
00070     boost::mutex::scoped_lock lock(mutex_);
00071     vital_checker_->poke();
00072     /* float image */
00073     cv::Mat height_map = cv::Mat(resolution_y_, resolution_x_, CV_32FC1);
00074     height_map = cv::Scalar::all(- FLT_MAX);
00075     pcl::PointCloud<pcl::PointXYZ> cloud;
00076     pcl::fromROSMsg(*msg, cloud);
00077     float max_height = - FLT_MAX;
00078     float min_height = FLT_MAX;
00079     for (size_t i = 0; i < cloud.points.size(); i++) {
00080       pcl::PointXYZ p = cloud.points[i];
00081       if (isnan(p.x) || isnan(p.y) || isnan(p.z)) {
00082         continue;
00083       }
00084       cv::Point index = toIndex(p);
00085       if (index.x >= 0 && index.x < resolution_x_ && 
00086           index.y >= 0 && index.y < resolution_y_) {
00087         /* Store min/max value for colorization */
00088         max_height = std::max(max_height, p.z);
00089         min_height = std::min(min_height, p.z);
00090         if (height_map.at<float>(index.y, index.x) < p.z) {
00091           height_map.at<float>(index.y, index.x) = p.z;
00092         }
00093       }
00094     }
00095     // Convert to sensor_msgs/Image
00096     cv_bridge::CvImage height_map_image(msg->header,
00097                                         sensor_msgs::image_encodings::TYPE_32FC1,
00098                                         height_map);
00099     pub_.publish(height_map_image.toImageMsg());
00100   }
00101 
00102   void HeightmapConverter::configCallback(Config &config, uint32_t level)
00103   {
00104     boost::mutex::scoped_lock lock(mutex_);
00105     min_x_ = config.min_x;
00106     max_x_ = config.max_x;
00107     min_y_ = config.min_y;
00108     max_y_ = config.max_y;
00109     resolution_x_ = config.resolution_x;
00110     resolution_y_ = config.resolution_y;
00111     jsk_recognition_msgs::HeightmapConfig heightmap_config;
00112     heightmap_config.min_x = min_x_;
00113     heightmap_config.min_y = min_y_;
00114     heightmap_config.max_x = max_x_;
00115     heightmap_config.max_y = max_y_;
00116     pub_config_.publish(heightmap_config);
00117   }
00118 
00119 }
00120 
00121 #include <pluginlib/class_list_macros.h>
00122 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::HeightmapConverter,
00123                         nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47