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 #include "jsk_pcl_ros/tf_listener_singleton.h"
00042 #include <pcl/common/transforms.h>
00043 #include <tf_conversions/tf_eigen.h>
00044 
00045 namespace jsk_pcl_ros
00046 {
00047   void HeightmapConverter::onInit()
00048   {
00049     DiagnosticNodelet::onInit();
00050     pub_config_ = pnh_->advertise<jsk_recognition_msgs::HeightmapConfig>(
00051       "output/config", 1, true);
00052     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00053     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00054       boost::bind (&HeightmapConverter::configCallback, this, _1, _2);
00055     srv_->setCallback (f);
00056 
00057     pnh_->param("fixed_frame_id", fixed_frame_id_, std::string("map"));
00058     pnh_->param("center_frame_id", center_frame_id_, std::string("BODY"));
00059     pnh_->param("projected_center_frame_id",
00060                 projected_center_frame_id_, std::string("BODY_on_map"));
00061     pnh_->param("use_projected_center", use_projected_center_, false);
00062 
00063     pnh_->param("max_queue_size", max_queue_size_, 10);
00064     pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00065 
00066     tf_ = TfListenerSingleton::getInstance();
00067 
00068     onInitPostProcess();
00069   }
00070   
00071   void HeightmapConverter::subscribe()
00072   {
00073     sub_ = pnh_->subscribe("input", max_queue_size_, &HeightmapConverter::convert, this);
00074   }
00075 
00076   void HeightmapConverter::unsubscribe()
00077   {
00078     sub_.shutdown();
00079   }
00080 
00081   void HeightmapConverter::convert(const sensor_msgs::PointCloud2::ConstPtr& msg)
00082   {
00083     boost::mutex::scoped_lock lock(mutex_);
00084     vital_checker_->poke();
00085     std_msgs::Header msg_header(msg->header);
00086     pcl::PointCloud<pcl::PointXYZ> transformed_cloud;
00087     if (use_projected_center_) {
00088       /* convert points */
00089       tf::StampedTransform ros_fixed_to_center;
00090       try {
00091         tf_->lookupTransform(fixed_frame_id_, center_frame_id_,
00092                              msg->header.stamp, ros_fixed_to_center);
00093       }
00094       catch (tf2::TransformException &e) {
00095         NODELET_ERROR("Transform error: %s", e.what());
00096         return;
00097       }
00098       double roll, pitch, yaw;
00099       tf::Vector3 pos = ros_fixed_to_center.getOrigin();
00100       ros_fixed_to_center.getBasis().getRPY(roll, pitch, yaw);
00101       Eigen::Affine3d fixed_to_center = (Eigen::Translation3d(pos[0], pos[1], 0) *
00102                                          Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()));
00103 
00104       tf::StampedTransform ros_msg_to_fixed;
00105       tf_->lookupTransform(msg->header.frame_id, fixed_frame_id_,
00106                            msg->header.stamp, ros_msg_to_fixed);
00107       Eigen::Affine3d msg_to_fixed;
00108       tf::transformTFToEigen(ros_msg_to_fixed, msg_to_fixed);
00109 
00110       pcl::PointCloud<pcl::PointXYZ> from_msg_cloud;
00111       pcl::fromROSMsg(*msg, from_msg_cloud);
00112       pcl::transformPointCloud(from_msg_cloud, transformed_cloud, msg_to_fixed * fixed_to_center);
00113 
00114       tf::StampedTransform tf_fixed_to_center;
00115       transformEigenToTF(fixed_to_center, tf_fixed_to_center);
00116       tf_fixed_to_center.frame_id_ = fixed_frame_id_;
00117       tf_fixed_to_center.child_frame_id_ = projected_center_frame_id_;
00118       tf_fixed_to_center.stamp_ = msg_header.stamp;
00119       tf_broadcaster_.sendTransform(tf_fixed_to_center);
00120 
00121       msg_header.frame_id = projected_center_frame_id_;
00122     } else {
00123       pcl::fromROSMsg(*msg, transformed_cloud);
00124     }
00125     /* float image */
00126     cv::Mat height_map = cv::Mat(resolution_y_, resolution_x_, CV_32FC2);
00127     height_map = cv::Scalar::all(- FLT_MAX);
00128 
00129     float max_height = - FLT_MAX;
00130     float min_height = FLT_MAX;
00131     for (size_t i = 0; i < transformed_cloud.points.size(); i++) {
00132       pcl::PointXYZ p = transformed_cloud.points[i];
00133       if (std::isnan(p.x) || std::isnan(p.y) || std::isnan(p.z)) {
00134         continue;
00135       }
00136       cv::Point index = toIndex(p);
00137       if (index.x >= 0 && index.x < resolution_x_ &&
00138           index.y >= 0 && index.y < resolution_y_) {
00139         /* Store min/max value for colorization */
00140         max_height = std::max(max_height, p.z);
00141         min_height = std::min(min_height, p.z);
00142         // accept maximum points
00143         if (height_map.at<cv::Vec2f>(index.y, index.x)[0] < p.z) {
00144           height_map.at<cv::Vec2f>(index.y, index.x)[0] = p.z;
00145           height_map.at<cv::Vec2f>(index.y, index.x)[1] = initial_probability_;
00146         }
00147       }
00148     }
00149     // Convert to sensor_msgs/Image
00150     cv_bridge::CvImage height_map_image(msg_header,
00151                                         sensor_msgs::image_encodings::TYPE_32FC2,
00152                                         height_map);
00153     pub_.publish(height_map_image.toImageMsg());
00154   }
00155 
00156   void HeightmapConverter::configCallback(Config &config, uint32_t level)
00157   {
00158     boost::mutex::scoped_lock lock(mutex_);
00159     min_x_ = config.min_x;
00160     max_x_ = config.max_x;
00161     min_y_ = config.min_y;
00162     max_y_ = config.max_y;
00163     resolution_x_ = config.resolution_x;
00164     resolution_y_ = config.resolution_y;
00165     initial_probability_ = config.initial_probability;
00166     jsk_recognition_msgs::HeightmapConfig heightmap_config;
00167     heightmap_config.min_x = min_x_;
00168     heightmap_config.min_y = min_y_;
00169     heightmap_config.max_x = max_x_;
00170     heightmap_config.max_y = max_y_;
00171     pub_config_.publish(heightmap_config);
00172   }
00173 
00174 }
00175 
00176 #include <pluginlib/class_list_macros.h>
00177 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::HeightmapConverter,
00178                         nodelet::Nodelet);


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