Skip to content

Commit

Permalink
Merge pull request #612 from garaemon/ycrcb-decomposer
Browse files Browse the repository at this point in the history
[jsk_perception] YCrCb decomposer
  • Loading branch information
garaemon committed Jan 20, 2015
2 parents c17b1a1 + 69f2ab5 commit 380508b
Show file tree
Hide file tree
Showing 5 changed files with 182 additions and 1 deletion.
13 changes: 13 additions & 0 deletions jsk_perception/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -91,3 +91,16 @@ Decompose BGR/RGB image into separate planes in [CIE-Lab color space](http://en.
* `~output/a` (`sensor_msgs/Image`)
* `~output/b` (`sensor_msgs/Image`)
L*, a and b separated planes. Each image has CV_8UC encoding.

### jsk\_perception/YCCDecomposer
Decompose BGR/RGB image into separate planes in [YCbCr color space](http://en.wikipedia.org/wiki/YCbCr).

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

Input image.
#### Publishing Topic
* `~output/y` (`sensor_msgs/Image`)
* `~output/cr` (`sensor_msgs/Image`)
* `~output/cb` (`sensor_msgs/Image`)
Y, Cr and Cb separated planes. Each image has CV_8UC encoding.
1 change: 1 addition & 0 deletions jsk_perception/catkin.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,7 @@ jsk_perception_nodelet(src/slic_superpixels.cpp "jsk_perception/SLICSuperPixels"
jsk_perception_nodelet(src/rgb_decomposer.cpp "jsk_perception/RGBDecomposer" "rgb_decomposer")
jsk_perception_nodelet(src/hsv_decomposer.cpp "jsk_perception/HSVDecomposer" "hsv_decomposer")
jsk_perception_nodelet(src/lab_decomposer.cpp "jsk_perception/LabDecomposer" "lab_decomposer")
jsk_perception_nodelet(src/ycc_decomposer.cpp "jsk_perception/YCCDecomposer" "ycc_decomposer")
jsk_perception_nodelet(src/contour_finder.cpp "jsk_perception/ContourFinder" "contour_finder")
jsk_perception_nodelet(src/snake_segmentation.cpp "jsk_perception/SnakeSegmentation" "snake_segmentation")
jsk_perception_nodelet(src/colorize_labels.cpp "jsk_perception/ColorizeLabels" "colorize_labels")
Expand Down
65 changes: 65 additions & 0 deletions jsk_perception/include/jsk_perception/ycc_decomposer.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
// -*- 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_YCC_DECOMPOSER_H_
#define JSK_PERCEPTION_YCC_DECOMPOSER_H_

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

namespace jsk_perception
{
class YCCDecomposer: public jsk_topic_tools::DiagnosticNodelet
{
public:
YCCDecomposer(): DiagnosticNodelet("YCCDecomposer") {}
protected:
virtual void onInit();
virtual void subscribe();
virtual void unsubscribe();
virtual void decompose(
const sensor_msgs::Image::ConstPtr& image_msg);
ros::Subscriber sub_;
ros::Publisher pub_y_;
ros::Publisher pub_cr_;
ros::Publisher pub_cb_;
private:

};
}


#endif
4 changes: 3 additions & 1 deletion jsk_perception/jsk_perception_nodelets.xml
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,9 @@
<class name="jsk_perception/LabDecomposer" type="jsk_perception::LabDecomposer"
base_class_type="nodelet::Nodelet">
</class>

<class name="jsk_perception/YCCDecomposer" type="jsk_perception::YCCDecomposer"
base_class_type="nodelet::Nodelet">
</class>
<class name="jsk_perception/RGBDecomposer" type="jsk_perception::RGBDecomposer"
base_class_type="nodelet::Nodelet">
<description>
Expand Down
100 changes: 100 additions & 0 deletions jsk_perception/src/ycc_decomposer.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
// -*- 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/ycc_decomposer.h"
#include <sensor_msgs/image_encodings.h>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>

namespace jsk_perception
{
void YCCDecomposer::onInit()
{
DiagnosticNodelet::onInit();
pub_y_ = advertise<sensor_msgs::Image>(*pnh_, "output/y", 1);
pub_cr_ = advertise<sensor_msgs::Image>(*pnh_, "output/cr", 1);
pub_cb_ = advertise<sensor_msgs::Image>(*pnh_, "output/cb", 1);
}

void YCCDecomposer::subscribe()
{
sub_ = pnh_->subscribe("input", 1, &YCCDecomposer::decompose, this);
}

void YCCDecomposer::unsubscribe()
{
sub_.shutdown();
}

void YCCDecomposer::decompose(
const sensor_msgs::Image::ConstPtr& image_msg)
{
cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
image_msg, image_msg->encoding);
cv::Mat image = cv_ptr->image;
cv::Mat ycc_image;
std::vector<cv::Mat> ycc_planes;
if (image_msg->encoding == sensor_msgs::image_encodings::BGR8) {
cv::cvtColor(image, ycc_image, CV_BGR2YCrCb);
}
else if (image_msg->encoding == sensor_msgs::image_encodings::RGB8) {
cv::cvtColor(image, ycc_image, CV_RGB2YCrCb);
}
else {
NODELET_ERROR("unsupported format to YCC: %s", image_msg->encoding.c_str());
return;
}
cv::split(ycc_image, ycc_planes);
cv::Mat y = ycc_planes[0];
cv::Mat cr = ycc_planes[1];
cv::Mat cb = ycc_planes[2];
pub_y_.publish(cv_bridge::CvImage(
image_msg->header,
sensor_msgs::image_encodings::MONO8,
y).toImageMsg());
pub_cr_.publish(cv_bridge::CvImage(
image_msg->header,
sensor_msgs::image_encodings::MONO8,
cr).toImageMsg());
pub_cb_.publish(cv_bridge::CvImage(
image_msg->header,
sensor_msgs::image_encodings::MONO8,
cb).toImageMsg());
}
}

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

0 comments on commit 380508b

Please sign in to comment.