Skip to content

Commit

Permalink
Merge pull request #1 from k-okada/color-filter
Browse files Browse the repository at this point in the history
use BGR2HSB, support H from 0-360 and 350 - 360+a
  • Loading branch information
iory authored Dec 22, 2016
2 parents afe7c3e + aff787c commit d43bbf0
Show file tree
Hide file tree
Showing 7 changed files with 155 additions and 39 deletions.
6 changes: 4 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,8 @@ generate_dynamic_reconfigure_options(
cfg/SimpleFlow.cfg
cfg/Threshold.cfg
cfg/RGBColorFilter.cfg
cfg/HSIColorFilter.cfg
cfg/HSLColorFilter.cfg
cfg/HSVColorFilter.cfg
cfg/WatershedSegmentation.cfg
)

Expand Down Expand Up @@ -155,7 +156,8 @@ opencv_apps_add_nodelet(discrete_fourier_transform discrete_fourier_transform/di
opencv_apps_add_nodelet(smoothing smoothing/smoothing src/nodelet/smoothing_nodelet.cpp) # ./tutorial_code/ImgProc/Smoothing.cpp
opencv_apps_add_nodelet(threshold threshold/threshold src/nodelet/threshold_nodelet.cpp) # ./tutorial_code/ImgProc/Threshold.cpp
opencv_apps_add_nodelet(rgb_color_filter rgb_color_filter/rgb_color_filter src/nodelet/color_filter_nodelet.cpp) # ./tutorial_code/ImgProc/Threshold_inRange.cpp
opencv_apps_add_nodelet(hsi_color_filter hsi_color_filter/hsi_color_filter src/nodelet/color_filter_nodelet.cpp) # ./tutorial_code/ImgProc/Threshold_inRange.cpp
opencv_apps_add_nodelet(hsl_color_filter hsl_color_filter/hsl_color_filter src/nodelet/color_filter_nodelet.cpp) # ./tutorial_code/ImgProc/Threshold_inRange.cpp
opencv_apps_add_nodelet(hsv_color_filter hsv_color_filter/hsv_color_filter src/nodelet/color_filter_nodelet.cpp) # ./tutorial_code/ImgProc/Threshold_inRange.cpp

# ImgTrans
opencv_apps_add_nodelet(edge_detection edge_detection/edge_detection src/nodelet/edge_detection_nodelet.cpp) # ./tutorial_code/ImgTrans/CannyDetector_Demo.cpp
Expand Down
18 changes: 18 additions & 0 deletions cfg/HSLColorFilter.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
#!/usr/bin/env python

PACKAGE='color_filter'

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

gen.add("use_camera_info", bool_t, 0, "Indicates that the camera_info topic should be subscribed to to get the default input_frame_id. Otherwise the frame from the image message will be used.", True)

gen.add ("h_limit_max", int_t, 0, "The maximum allowed field value Hue", 360, 0, 360)
gen.add ("h_limit_min", int_t, 0, "The minimum allowed field value Hue", 0, 0, 360)
gen.add ("s_limit_max", int_t, 0, "The maximum allowed field value Saturation", 256, 0, 256)
gen.add ("s_limit_min", int_t, 0, "The minimum allowed field value Saturation", 0, 0, 256)
gen.add ("l_limit_max", int_t, 0, "The maximum allowed field value Lightness", 256, 0, 256)
gen.add ("l_limit_min", int_t, 0, "The minimum allowed field value Lightness", 0, 0, 256)

exit(gen.generate(PACKAGE, "color_filter", "HSLColorFilter"))
18 changes: 18 additions & 0 deletions cfg/HSVColorFilter.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
#!/usr/bin/env python

PACKAGE='color_filter'

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

gen.add("use_camera_info", bool_t, 0, "Indicates that the camera_info topic should be subscribed to to get the default input_frame_id. Otherwise the frame from the image message will be used.", True)

gen.add ("h_limit_max", int_t, 0, "The maximum allowed field value Hue", 360, 0, 360)
gen.add ("h_limit_min", int_t, 0, "The minimum allowed field value Hue", 0, 0, 360)
gen.add ("s_limit_max", int_t, 0, "The maximum allowed field value Saturation", 256, 0, 256)
gen.add ("s_limit_min", int_t, 0, "The minimum allowed field value Saturation", 0, 0, 256)
gen.add ("v_limit_max", int_t, 0, "The maximum allowed field value Value", 256, 0, 256)
gen.add ("v_limit_min", int_t, 0, "The minimum allowed field value Value", 0, 0, 256)

exit(gen.generate(PACKAGE, "color_filter", "HSVColorFilter"))
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<launch>
<arg name="node_name" default="hsi_color_filter" />
<arg name="node_name" default="hsl_color_filter" />

<arg name="image" default="image" doc="The image topic. Should be remapped to the name of the real image topic." />

Expand All @@ -10,20 +10,19 @@
<arg name="h_limit_min" default="0" doc="The minimum allowed field value Hue" />
<arg name="s_limit_max" default="255" doc="The maximum allowed field value Saturation" />
<arg name="s_limit_min" default="150" doc="The minimum allowed field value Saturation" />
<arg name="i_limit_max" default="255" doc="The maximum allowed field value Intensity" />
<arg name="i_limit_min" default="50" doc="The minimum allowed field value Intensity" />
<arg name="l_limit_max" default="255" doc="The maximum allowed field value Luminance" />
<arg name="l_limit_min" default="50" doc="The minimum allowed field value Luminance" />

<!-- color_filter.cpp -->
<node name="$(arg node_name)" pkg="opencv_apps" type="hsi_color_filter" output="screen">
<node name="$(arg node_name)" pkg="opencv_apps" type="hsl_color_filter" output="screen">
<remap from="image" to="$(arg image)" />
<!-- <remap from="image" to="/image_publisher/output" /> -->
<param name="use_camera_info" value="$(arg use_camera_info)" />
<param name="debug_view" value="$(arg debug_view)" />
<param name="h_limit_max" value="$(arg h_limit_max)" />
<param name="h_limit_min" value="$(arg h_limit_min)" />
<param name="s_limit_max" value="$(arg s_limit_max)" />
<param name="s_limit_min" value="$(arg s_limit_min)" />
<param name="i_limit_max" value="$(arg i_limit_max)" />
<param name="i_limit_min" value="$(arg i_limit_min)" />
<param name="l_limit_max" value="$(arg l_limit_max)" />
<param name="l_limit_min" value="$(arg l_limit_min)" />
</node>
</launch>
8 changes: 6 additions & 2 deletions nodelet_plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,12 @@
<description>Nodelet of rgb color filter</description>
</class>

<class name="hsi_color_filter/hsi_color_filter" type="color_filter::HSIColorFilterNodelet" base_class_type="nodelet::Nodelet">
<description>Nodelet of hsi color filter</description>
<class name="hls_color_filter/hsi_color_filter" type="color_filter::HLSColorFilterNodelet" base_class_type="nodelet::Nodelet">
<description>Nodelet of hls color filter</description>
</class>

<class name="hsv_color_filter/hsi_color_filter" type="color_filter::HSVColorFilterNodelet" base_class_type="nodelet::Nodelet">
<description>Nodelet of hsv color filter</description>
</class>

<class name="watershed_segmentation/watershed_segmentation" type="watershed_segmentation::WatershedSegmentationNodelet" base_class_type="nodelet::Nodelet">
Expand Down
117 changes: 96 additions & 21 deletions src/nodelet/color_filter_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,13 @@

#include <dynamic_reconfigure/server.h>
#include "opencv_apps/RGBColorFilterConfig.h"
#include "opencv_apps/HSIColorFilterConfig.h"
#include "opencv_apps/HSLColorFilterConfig.h"
#include "opencv_apps/HSVColorFilterConfig.h"

namespace color_filter {
class RGBColorFilter;
class HSIColorFilter;
class HSLColorFilter;
class HSVColorFilter;

template <typename Config>
class ColorFilterNodelet : public opencv_apps::Nodelet
Expand Down Expand Up @@ -223,52 +225,123 @@ class RGBColorFilterNodelet
}
};

class HSIColorFilterNodelet
: public ColorFilterNodelet<color_filter::HSIColorFilterConfig> {
class HSLColorFilterNodelet
: public ColorFilterNodelet<color_filter::HSLColorFilterConfig> {
protected:
int h_min_;
int h_max_;
int s_min_;
int s_max_;
int i_min_;
int i_max_;
int l_min_;
int l_max_;

virtual void reconfigureCallback(color_filter::HSIColorFilterConfig& config,
virtual void reconfigureCallback(color_filter::HSLColorFilterConfig& config,
uint32_t level) {
boost::mutex::scoped_lock lock(mutex_);
config_ = config;
h_max_ = config.h_limit_max;
h_min_ = config.h_limit_min;
s_max_ = config.s_limit_max;
s_min_ = config.s_limit_min;
i_max_ = config.i_limit_max;
i_min_ = config.i_limit_min;
l_max_ = config.l_limit_max;
l_min_ = config.l_limit_min;
updateCondition();
}

virtual void updateCondition() {
if (h_max_ < h_min_) std::swap(h_max_, h_min_);
if (s_max_ < s_min_) std::swap(s_max_, s_min_);
if (i_max_ < i_min_) std::swap(i_max_, i_min_);
lower_color_range_ = cv::Scalar(h_min_, s_min_, i_min_, 0);
upper_color_range_ = cv::Scalar(h_max_, s_max_, i_max_, 0);
if (l_max_ < l_min_) std::swap(l_max_, l_min_);
lower_color_range_ = cv::Scalar(h_min_/2, l_min_, s_min_, 0);
upper_color_range_ = cv::Scalar(h_max_/2, l_max_, s_max_, 0);
}

virtual void filter(const cv::Mat& input_image, cv::Mat& output_image) {
cv::Mat hls_image;
cv::cvtColor(input_image, hls_image, cv::COLOR_BGR2HLS);
if ( lower_color_range_[0] < upper_color_range_[0] ) {
cv::inRange(hls_image, lower_color_range_, upper_color_range_,
output_image);
}else {
cv::Scalar lower_color_range_0 = cv::Scalar( 0, l_min_, s_min_, 0);
cv::Scalar upper_color_range_0 = cv::Scalar(h_max_/2, l_max_, s_max_, 0);
cv::Scalar lower_color_range_360 = cv::Scalar(h_min_/2, l_min_, s_min_, 0);
cv::Scalar upper_color_range_360 = cv::Scalar( 360/2, l_max_, s_max_, 0);
cv::Mat output_image_0, output_image_360;
cv::inRange(hls_image, lower_color_range_0, upper_color_range_0, output_image_0);
cv::inRange(hls_image, lower_color_range_360, upper_color_range_360, output_image_360);
output_image = output_image_0 | output_image_360;
}
}

public:
virtual void onInit() {
h_max_ = 360;
h_min_ = 0;
s_max_ = 256;
s_min_ = 0;
l_max_ = 256;
l_min_ = 0;

ColorFilterNodelet::onInit();
}
};

class HSVColorFilterNodelet
: public ColorFilterNodelet<color_filter::HSVColorFilterConfig> {
protected:
int h_min_;
int h_max_;
int s_min_;
int s_max_;
int v_min_;
int v_max_;

virtual void reconfigureCallback(color_filter::HSVColorFilterConfig& config,
uint32_t level) {
boost::mutex::scoped_lock lock(mutex_);
config_ = config;
h_max_ = config.h_limit_max;
h_min_ = config.h_limit_min;
s_max_ = config.s_limit_max;
s_min_ = config.s_limit_min;
v_max_ = config.v_limit_max;
v_min_ = config.v_limit_min;
updateCondition();
}

virtual void updateCondition() {
if (s_max_ < s_min_) std::swap(s_max_, s_min_);
if (v_max_ < v_min_) std::swap(v_max_, v_min_);
lower_color_range_ = cv::Scalar(h_min_/2, s_min_, v_min_, 0);
upper_color_range_ = cv::Scalar(h_max_/2, s_max_, v_max_, 0);
}

virtual void filter(const cv::Mat& input_image, cv::Mat& output_image) {
cv::Mat hsv_image;
cv::cvtColor(input_image, hsv_image, cv::COLOR_BGR2HSV);
cv::inRange(hsv_image, lower_color_range_, upper_color_range_,
output_image);
if ( lower_color_range_[0] < upper_color_range_[0] ) {
cv::inRange(hsv_image, lower_color_range_, upper_color_range_,
output_image);
}else {
cv::Scalar lower_color_range_0 = cv::Scalar( 0, s_min_, v_min_, 0);
cv::Scalar upper_color_range_0 = cv::Scalar(h_max_/2, s_max_, v_max_, 0);
cv::Scalar lower_color_range_360 = cv::Scalar(h_min_/2, s_min_, v_min_, 0);
cv::Scalar upper_color_range_360 = cv::Scalar( 360/2, s_max_, v_max_, 0);
cv::Mat output_image_0, output_image_360;
cv::inRange(hsv_image, lower_color_range_0, upper_color_range_0, output_image_0);
cv::inRange(hsv_image, lower_color_range_360, upper_color_range_360, output_image_360);
output_image = output_image_0 | output_image_360;
}
}

public:
virtual void onInit() {
h_max_ = 255;
h_max_ = 360;
h_min_ = 0;
s_max_ = 255;
s_max_ = 256;
s_min_ = 0;
i_max_ = 255;
i_min_ = 0;
v_max_ = 256;
v_min_ = 0;

ColorFilterNodelet::onInit();
}
Expand All @@ -278,6 +351,8 @@ class HSIColorFilterNodelet

#include <pluginlib/class_list_macros.h>
typedef color_filter::RGBColorFilterNodelet RGBColorFilterNodelet;
typedef color_filter::HSIColorFilterNodelet HSIColorFilterNodelet;
typedef color_filter::HSLColorFilterNodelet HSLColorFilterNodelet;
typedef color_filter::HSVColorFilterNodelet HSVColorFilterNodelet;
PLUGINLIB_EXPORT_CLASS(color_filter::RGBColorFilterNodelet, nodelet::Nodelet);
PLUGINLIB_EXPORT_CLASS(color_filter::HSIColorFilterNodelet, nodelet::Nodelet);
PLUGINLIB_EXPORT_CLASS(color_filter::HSLColorFilterNodelet, nodelet::Nodelet);
PLUGINLIB_EXPORT_CLASS(color_filter::HSVColorFilterNodelet, nodelet::Nodelet);
Original file line number Diff line number Diff line change
Expand Up @@ -7,23 +7,23 @@
<node name="image_view" pkg="image_view" type="image_view" args="image:=image_rect_color" if="$(arg gui)" />

<!-- color_filter.cpp -->
<include file="$(find opencv_apps)/launch/hsi_color_filter.launch" >
<include file="$(find opencv_apps)/launch/hsl_color_filter.launch" >
<arg name="debug_view" value="$(arg gui)" />
<arg name="image" value="image_rect_color" />
<arg name="h_limit_max" value="50" />
<arg name="h_limit_min" value="0" />
<arg name="s_limit_max" value="200" />
<arg name="s_limit_min" value="90" />
<arg name="i_limit_max" value="255" />
<arg name="i_limit_min" value="60" />
<arg name="l_limit_max" value="255" />
<arg name="l_limit_min" value="60" />
</include>

<!-- Test Codes -->
<node name="hsi_color_filter_saver" pkg="image_view" type="image_saver" args="image:=hsi_color_filter/image" >
<param name="filename_format" value="$(find opencv_apps)/test/hsi_color_filter.png"/>
<node name="hsl_color_filter_saver" pkg="image_view" type="image_saver" args="image:=hsl_color_filter/image" >
<param name="filename_format" value="$(find opencv_apps)/test/hsl_color_filter.png"/>
</node>
<param name="hsi_color_filter_test/topic" value="hsi_color_filter/image" />
<test test-name="hsi_color_filter_test" pkg="rostest" type="hztest" name="hsi_color_filter_test" >
<param name="hsl_color_filter_test/topic" value="hsl_color_filter/image" />
<test test-name="hsl_color_filter_test" pkg="rostest" type="hztest" name="hsl_color_filter_test" >
<param name="hz" value="20" />
<param name="hzerror" value="15" />
<param name="test_duration" value="5.0" />
Expand Down

0 comments on commit d43bbf0

Please sign in to comment.