Skip to content

Commit

Permalink
Merge pull request #613 from garaemon/single-channel-histogram
Browse files Browse the repository at this point in the history
[jsk_perception] SingleChannelHistogram to compute histogram of MONO8 image
  • Loading branch information
garaemon committed Jan 20, 2015
2 parents 380508b + b494669 commit 9deb0e7
Show file tree
Hide file tree
Showing 6 changed files with 254 additions and 0 deletions.
21 changes: 21 additions & 0 deletions jsk_perception/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -104,3 +104,24 @@ Decompose BGR/RGB image into separate planes in [YCbCr color space](http://en.wi
* `~output/cr` (`sensor_msgs/Image`)
* `~output/cb` (`sensor_msgs/Image`)
Y, Cr and Cb separated planes. Each image has CV_8UC encoding.

### jsk\_perception/SingleChannelHistogram
Compute histogram of single channel image.

#### Subscribing Topic
* `~input` (`sensor_msgs/Image`)

Input image. It should has CV_8UC1 as encoding.

* `~input/mask` (`sensor_msgs/Image`)

Mask image. if `~use_mask` is true, histogram is computed with this mask image.
#### Publishing Topic
* `~output` (`jsk_pcl_ros/ColorHistogram`)

Histogram of `~input` image.

#### Parameters
* `~use_mask` (Boolean, default: `false`)

If this parameter is set true, histogram is computed with mask image.
2 changes: 2 additions & 0 deletions jsk_perception/catkin.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ endif()

# Dynamic reconfigure support
generate_dynamic_reconfigure_options(
cfg/SingleChannelHistogram.cfg
cfg/ColorHistogramLabelMatch.cfg
cfg/GridLabel.cfg
cfg/SLICSuperPixels.cfg
Expand Down Expand Up @@ -104,6 +105,7 @@ jsk_perception_nodelet(src/colorize_labels.cpp "jsk_perception/ColorizeLabels" "
jsk_perception_nodelet(src/grid_label.cpp "jsk_perception/GridLabel" "grid_label")
jsk_perception_nodelet(src/color_histogram_label_match.cpp "jsk_perception/ColorHistogramLabelMatch" "color_histogram_label_match")
jsk_perception_nodelet(src/apply_mask_image.cpp "jsk_perception/ApplyMaskImage" "apply_mask_image")
jsk_perception_nodelet(src/single_channel_histogram.cpp "jsk_perception/SingleChannelHistogram" "single_channel_histogram")
# compiling jsk_perception library for nodelet
add_library(${PROJECT_NAME} SHARED ${jsk_perception_nodelet_sources}
${CMAKE_CURRENT_BINARY_DIR}/build/patched-SLIC-Superpixels/slic.cpp)
Expand Down
16 changes: 16 additions & 0 deletions jsk_perception/cfg/SingleChannelHistogram.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
#!/usr/bin/env python

PACKAGE='jsk_perception'
try:
import imp
imp.find_module(PACKAGE)
from dynamic_reconfigure.parameter_generator_catkin import *
except:
import roslib; roslib.load_manifest(PACKAGE)
from dynamic_reconfigure.parameter_generator import *

gen = ParameterGenerator()

gen.add("hist_size", int_t, 0, "the number of bins", 10, 1, 255)

exit(gen.generate(PACKAGE, "jsk_perception", "SingleChannelHistogram"))
87 changes: 87 additions & 0 deletions jsk_perception/include/jsk_perception/single_channel_histogram.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
// -*- mode: c++ -*-
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2015, JSK Lab
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/o2r other materials provided
* with the distribution.
* * Neither the name of the JSK Lab nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/


#ifndef JSK_PERCEPTION_SINGLE_CHANNEL_HISTOGRAM_H_
#define JSK_PERCEPTION_SINGLE_CHANNEL_HISTOGRAM_H_

#include <jsk_topic_tools/diagnostic_nodelet.h>
#include <sensor_msgs/Image.h>
#include <jsk_pcl_ros/ColorHistogram.h>

#include <dynamic_reconfigure/server.h>
#include <jsk_perception/SingleChannelHistogramConfig.h>

#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/exact_time.h>
#include <message_filters/sync_policies/approximate_time.h>

namespace jsk_perception
{
class SingleChannelHistogram: public jsk_topic_tools::DiagnosticNodelet
{
public:
typedef message_filters::sync_policies::ApproximateTime<
sensor_msgs::Image,
sensor_msgs::Image > SyncPolicy;
typedef SingleChannelHistogramConfig Config;
SingleChannelHistogram(): DiagnosticNodelet("SingleChannelHistogram") {}
protected:
virtual void onInit();
virtual void subscribe();
virtual void unsubscribe();
virtual void compute(
const sensor_msgs::Image::ConstPtr& msg);
virtual void compute(
const sensor_msgs::Image::ConstPtr& msg,
const sensor_msgs::Image::ConstPtr& mask_msg);
virtual void configCallback(Config &config, uint32_t level);

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
message_filters::Subscriber<sensor_msgs::Image> sub_image_;
message_filters::Subscriber<sensor_msgs::Image> sub_mask_;
boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
bool use_mask_;
ros::Subscriber sub_;
ros::Publisher pub_;
boost::mutex mutex_;
int hist_size_;
private:

};
}

#endif
4 changes: 4 additions & 0 deletions jsk_perception/jsk_perception_nodelets.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,8 @@
<library path="lib/libjsk_perception">
<class name="jsk_perception/SingleChannelHistogram"
type="jsk_perception::SingleChannelHistogram"
base_class_type="nodelet::Nodelet">
</class>
<class name="jsk_perception/ColorHistogramLabelMatch"
type="jsk_perception::ColorHistogramLabelMatch"
base_class_type="nodelet::Nodelet">
Expand Down
124 changes: 124 additions & 0 deletions jsk_perception/src/single_channel_histogram.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,124 @@
// -*- mode: c++ -*-
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2015, JSK Lab
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/o2r other materials provided
* with the distribution.
* * Neither the name of the JSK Lab nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include "jsk_perception/single_channel_histogram.h"
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>

namespace jsk_perception
{
void SingleChannelHistogram::onInit()
{
DiagnosticNodelet::onInit();
pnh_->param("use_mask", use_mask_, false);
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind (
&SingleChannelHistogram::configCallback, this, _1, _2);
srv_->setCallback (f);

pub_ = advertise<jsk_pcl_ros::ColorHistogram>(
*pnh_, "output", 1);
}

void SingleChannelHistogram::subscribe()
{
if (use_mask_) {
sub_image_.subscribe(*pnh_, "input", 1);
sub_mask_.subscribe(*pnh_, "input/mask", 1);
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
sync_->connectInput(sub_image_, sub_mask_);
sync_->registerCallback(boost::bind(&SingleChannelHistogram::compute,
this, _1, _2));
}
else {
sub_ = pnh_->subscribe("input", 1,
&SingleChannelHistogram::compute,
this);
}
}

void SingleChannelHistogram::unsubscribe()
{
if (use_mask_) {
sub_image_.unsubscribe();
sub_mask_.unsubscribe();
}
else {
sub_.shutdown();
}
}

void SingleChannelHistogram::compute(
const sensor_msgs::Image::ConstPtr& msg,
const sensor_msgs::Image::ConstPtr& mask_msg)
{
boost::mutex::scoped_lock lock(mutex_);
cv::Mat image = cv_bridge::toCvCopy(msg, msg->encoding)->image;
cv::Mat mask;
if (mask_msg) {
mask = cv_bridge::toCvCopy(mask_msg, mask_msg->encoding)->image;
}
float range[] = { 0, 256 } ;
const float* histRange = { range };
cv::MatND hist;
bool uniform = true; bool accumulate = false;

cv::calcHist(&image, 1, 0, mask, hist, 1, &hist_size_,
&histRange, uniform, accumulate);
jsk_pcl_ros::ColorHistogram histogram;
histogram.header = msg->header;
for (int i = 0; i < hist_size_; i++) {
histogram.histogram.push_back(hist.at<float>(0, i));
}
pub_.publish(histogram);
}

void SingleChannelHistogram::compute(
const sensor_msgs::Image::ConstPtr& msg)
{
compute(msg, sensor_msgs::Image::ConstPtr());
}

void SingleChannelHistogram::configCallback(
Config &config, uint32_t level)
{
boost::mutex::scoped_lock lock(mutex_);
hist_size_ = config.hist_size;
}
}

#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS (jsk_perception::SingleChannelHistogram, nodelet::Nodelet);

0 comments on commit 9deb0e7

Please sign in to comment.