mask_image_to_point_indices_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 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros_utils/mask_image_to_point_indices.h"
00037 #include "jsk_recognition_utils/pcl_conversion_util.h"
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 
00041 namespace jsk_pcl_ros_utils
00042 {
00043   void MaskImageToPointIndices::onInit()
00044   {
00045     DiagnosticNodelet::onInit();
00046     pnh_->param("use_multi_channels", use_multi_channels_, false);
00047     pnh_->param("target_channel", target_channel_, -1);
00048 
00049     if (use_multi_channels_ && target_channel_ < 0) {
00050       pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/all_indices", 1);
00051     } else {
00052       pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
00053     }
00054     onInitPostProcess();
00055   }
00056 
00057   void MaskImageToPointIndices::subscribe()
00058   {
00059     sub_ = pnh_->subscribe("input", 1,
00060                            &MaskImageToPointIndices::indices,
00061                            this);
00062   }
00063 
00064   void MaskImageToPointIndices::unsubscribe()
00065   {
00066     sub_.shutdown();
00067   }
00068 
00069   void MaskImageToPointIndices::indices(
00070     const sensor_msgs::Image::ConstPtr& image_msg)
00071   {
00072     vital_checker_->poke();
00073     if (use_multi_channels_) {
00074       cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(image_msg);
00075       cv::Mat image = cv_ptr->image;
00076       if (target_channel_ < 0) {
00077         jsk_recognition_msgs::ClusterPointIndices cluster_msg;
00078         cluster_msg.header = image_msg->header;
00079         cluster_msg.cluster_indices.resize(image.channels());
00080         for (size_t c = 0; c < image.channels(); ++c) {
00081           PCLIndicesMsg &indices_msg = cluster_msg.cluster_indices[c];
00082           indices_msg.header = image_msg->header;
00083           for (size_t j = 0; j < image.rows; j++) {
00084             for (size_t i = 0; i < image.cols; i++) {
00085               if (image.data[j * image.step + i * image.elemSize() + c] > 127) {
00086                 indices_msg.indices.push_back(j * image.cols + i);
00087               }
00088             }
00089           }
00090         }
00091         pub_.publish(cluster_msg);
00092       } else {
00093         if (target_channel_ > image.channels() - 1) {
00094           NODELET_ERROR("target_channel_ is %d, but image has %d channels",
00095                         target_channel_, image.channels());
00096           return;
00097         }
00098         PCLIndicesMsg indices_msg;
00099         indices_msg.header = image_msg->header;
00100         for (size_t j = 0; j < image.rows; j++) {
00101           for (size_t i = 0; i < image.cols; i++) {
00102             if (image.data[j * image.step + i * image.elemSize() + target_channel_] > 127) {
00103               indices_msg.indices.push_back(j * image.cols + i);
00104             }
00105           }
00106         }
00107         pub_.publish(indices_msg);
00108       }
00109     } else {
00110       cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00111         image_msg, sensor_msgs::image_encodings::TYPE_8UC1);
00112       cv::Mat image = cv_ptr->image;
00113       PCLIndicesMsg indices_msg;
00114       indices_msg.header = image_msg->header;
00115       for (size_t j = 0; j < image.rows; j++) {
00116         for (size_t i = 0; i < image.cols; i++) {
00117           if (image.at<uchar>(j, i) > 127) {
00118             indices_msg.indices.push_back(j * image.cols + i);
00119           }
00120         }
00121       }
00122       pub_.publish(indices_msg);
00123     }
00124   }
00125 }
00126 
00127 #include <pluginlib/class_list_macros.h>
00128 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::MaskImageToPointIndices, nodelet::Nodelet);


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:40:52