Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/mask_image_to_point_indices.h"
00037 #include "jsk_pcl_ros/pcl_conversion_util.h"
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040
00041 namespace jsk_pcl_ros
00042 {
00043 void MaskImageToPointIndices::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
00047 }
00048
00049 void MaskImageToPointIndices::subscribe()
00050 {
00051 sub_ = pnh_->subscribe("input", 1,
00052 &MaskImageToPointIndices::indices,
00053 this);
00054 }
00055
00056 void MaskImageToPointIndices::unsubscribe()
00057 {
00058 sub_.shutdown();
00059 }
00060
00061 void MaskImageToPointIndices::updateDiagnostic(
00062 diagnostic_updater::DiagnosticStatusWrapper &stat)
00063 {
00064 if (vital_checker_->isAlive()) {
00065 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00066 "MaskImageToPointIndices running");
00067 }
00068 else {
00069 jsk_topic_tools::addDiagnosticErrorSummary(
00070 "MaskImageToPointIndices", vital_checker_, stat);
00071 }
00072 }
00073
00074 void MaskImageToPointIndices::indices(
00075 const sensor_msgs::Image::ConstPtr& image_msg)
00076 {
00077 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00078 image_msg, sensor_msgs::image_encodings::MONO8);
00079 cv::Mat image = cv_ptr->image;
00080 PCLIndicesMsg indices_msg;
00081 indices_msg.header = image_msg->header;
00082 for (size_t j = 0; j < image.rows; j++) {
00083 for (size_t i = 0; i < image.cols; i++) {
00084 if (image.at<uchar>(j, i) == 255) {
00085 indices_msg.indices.push_back(j * image.cols + i);
00086 }
00087 }
00088 }
00089 pub_.publish(indices_msg);
00090 }
00091 }
00092
00093 #include <pluginlib/class_list_macros.h>
00094 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::MaskImageToPointIndices, nodelet::Nodelet);