kmeans.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #include "jsk_perception/kmeans.h"
39 #include <boost/assign.hpp>
42 #include <cv_bridge/cv_bridge.h>
43 #include <opencv2/opencv.hpp>
44 
45 namespace jsk_perception
46 {
48  {
49  DiagnosticNodelet::onInit();
50  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51  dynamic_reconfigure::Server<Config>::CallbackType f =
52  boost::bind (&KMeans::configCallback, this, _1, _2);
53  srv_->setCallback (f);
54 
55  pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
57  }
58 
60  {
61  sub_ = pnh_->subscribe("input", 1, &KMeans::apply, this);
62  ros::V_string names = boost::assign::list_of("~input");
64  }
65 
67  {
68  sub_.shutdown();
69  }
70 
72  Config &config, uint32_t level)
73  {
74  boost::mutex::scoped_lock lock(mutex_);
75  n_clusters_ = config.n_clusters;
76  }
77 
79  const sensor_msgs::Image::ConstPtr& image_msg)
80  {
81  if ((image_msg->width == 0) && (image_msg->height == 0)) {
82  ROS_WARN("invalid image input");
83  return;
84  }
86  image_msg, image_msg->encoding);
87  cv::Mat image = cv_ptr->image;
88 
89  cv::Mat reshaped_img = image.reshape(1, image.cols * image.rows);
90  cv::Mat reshaped_img32f;
91  reshaped_img.convertTo(reshaped_img32f, CV_32FC1, 1.0 / 255.0);
92  cv::Mat labels;
93  cv::TermCriteria criteria = cv::TermCriteria(CV_TERMCRIT_EPS+CV_TERMCRIT_ITER, 10, 1.0);
94  cv::Mat centers;
95  cv::kmeans(reshaped_img32f, n_clusters_, labels, criteria, /*attempts=*/1, /*flags=*/cv::KMEANS_PP_CENTERS, centers);
96 
97  cv::Mat rgb_image(image.rows, image.cols, CV_8UC3);
98  cv::MatIterator_<cv::Vec3b> rgb_first = rgb_image.begin<cv::Vec3b>();
99  cv::MatIterator_<cv::Vec3b> rgb_last = rgb_image.end<cv::Vec3b>();
100  cv::MatConstIterator_<int> label_first = labels.begin<int>();
101 
102  cv::Mat centers_u8;
103  centers.convertTo(centers_u8, CV_8UC1, 255.0);
104  cv::Mat centers_u8c3 = centers_u8.reshape(3);
105 
106  while ( rgb_first != rgb_last ) {
107  const cv::Vec3b& rgb = centers_u8c3.ptr<cv::Vec3b>(*label_first)[0];
108  *rgb_first = rgb;
109  ++rgb_first;
110  ++label_first;
111  }
112 
114  image_msg->header,
115  image_msg->encoding,
116  rgb_image).toImageMsg());
117  }
118 
119 }
120 
f
virtual void apply(const sensor_msgs::Image::ConstPtr &image_msg)
Definition: kmeans.cpp:78
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber sub_
Definition: kmeans.h:61
virtual void configCallback(Config &config, uint32_t level)
Definition: kmeans.cpp:71
PLUGINLIB_EXPORT_CLASS(jsk_perception::KMeans, nodelet::Nodelet)
#define ROS_WARN(...)
std::vector< std::string > V_string
virtual void unsubscribe()
Definition: kmeans.cpp:66
boost::shared_ptr< ros::NodeHandle > pnh_
bool warnNoRemap(const std::vector< std::string > names)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
mutex_t * lock
ros::Publisher pub_
Definition: kmeans.h:62
jsk_perception::KMeansConfig Config
Definition: kmeans.h:51
virtual void subscribe()
Definition: kmeans.cpp:59
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: kmeans.h:63
virtual void onInit()
Definition: kmeans.cpp:47
sensor_msgs::ImagePtr toImageMsg() const
boost::mutex mutex_
Definition: kmeans.h:60


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27