Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Blob detection nodelet #130

Open
wants to merge 19 commits into
base: indigo
Choose a base branch
from
Open
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
update
HuiShiSerenaShi committed Feb 3, 2022

Verified

This commit was created on GitHub.com and signed with GitHub’s verified signature.
commit aac32d230f5bed7a01e6544ccfe585b4f712078e
10 changes: 5 additions & 5 deletions cfg/BlobDetection.cfg
Original file line number Diff line number Diff line change
@@ -72,12 +72,12 @@ gen.add("minInertiaRatio", double_t, 0, "minInertiaRatio", 0, 0, 1)
gen.add("maxInertiaRatio", double_t, 0, "maxInertiaRatio", 1, 0, 1)


blobMsgType = gen.enum([ gen.const("Blob", str_t, "Blob", "Blob"),
gen.const("BlobArray", str_t, "BlobArray", "BlobArray"),
gen.const("BlobArrayStamped", str_t, "BlobArrayStamped", "BlobArrayStamped")],
"An enum to set blobMsgType")
morphology_ex_type = gen.enum([ gen.const("off", str_t, "off", "off"),
gen.const("opening", str_t, "opening", "opening"),
gen.const("closing", str_t, "closing", "closing")],
"An enum to set morphology_ex_type")

gen.add("blobMsgType", str_t, 0, "blobMsgType edited via an enum", "Blob", edit_method=blobMsgType)
gen.add("morphology_ex_type", str_t, 0, "morphology_ex_type edited via an enum", "off", edit_method=morphology_ex_type)

# debug_view_type_enum = gen.enum([ gen.const("Input", int_t, 0, "Input image"),
# gen.const("Blur", int_t, 1, "GaussianBlur image"),
161 changes: 161 additions & 0 deletions config/blob_detection.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,161 @@
Panels:
- Class: rviz/Displays
Help Height: 172
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /Image1
- /Image2
- /Image3
Splitter Ratio: 0.5
Tree Height: 848
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: Image
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /blob_detection/image
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /blob_detection/thresholded_image
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /blob_detection/morphology_ex_image
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: map
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 10
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.785398006439209
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.785398006439209
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1472
Hide Left Dock: false
Hide Right Dock: false
Image:
collapsed: false
QMainWindow State: 000000ff00000000fd00000004000000000000026b00000482fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b000000da00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000dafb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000008600000482000001de00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006503000004b7000003880000026b000001d6fb0000000a0049006d00610067006503000005cf000002400000026b000000e200000001000001b400000482fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000086000004820000017800fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b20000000000000000000000020000097a000000a9fc0100000002fb0000000a0049006d00610067006503000003ce0000016600000280000001e0fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000097a00000073fc0100000002fb0000000800540069006d006501000000000000097a000006de00fffffffb0000000800540069006d006501000000000000045000000000000000000000053d0000048200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 2426
X: 134
Y: 68
69 changes: 69 additions & 0 deletions config/blob_detection_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
blobColor: 255
debug_view: false
filterByArea: true
filterByCircularity: true
filterByColor: true
filterByConvexity: true
filterByInertia: true
highHue: 179.0
highSat: 255.0
highVal: 255.0
image:
compressed:
format: jpeg
jpeg_quality: 80
png_level: 9
compressedDepth:
depth_max: 10.0
depth_quantization: 100.0
png_level: 9
theora:
keyframe_frequency: 64
optimize_for: 1
quality: 31
target_bitrate: 800000
lowHue: 80.55000000000001
lowSat: 0.0
lowVal: 0.0
maxArea: 9000000
maxCircularity: 1.0
maxConvexity: 1.0
maxInertiaRatio: 1.0
minArea: 5000
minCircularity: 0.0
minConvexity: 0.0
minDistBetweenBlobs: 100
minInertiaRatio: 0.0
morphology_ex_image:
compressed:
format: jpeg
jpeg_quality: 80
png_level: 9
compressedDepth:
depth_max: 10.0
depth_quantization: 100.0
png_level: 9
theora:
keyframe_frequency: 64
optimize_for: 1
quality: 31
target_bitrate: 800000
morphology_ex_kernel_size: 16
morphology_ex_type: opening
num_worker_threads: 1
queue_size: 3
thresholded_image:
compressed:
format: jpeg
jpeg_quality: 80
png_level: 9
compressedDepth:
depth_max: 10.0
depth_quantization: 100.0
png_level: 9
theora:
keyframe_frequency: 64
optimize_for: 1
quality: 31
target_bitrate: 800000
use_camera_info: false
4 changes: 4 additions & 0 deletions launch/blob_detection.launch
Original file line number Diff line number Diff line change
@@ -7,6 +7,8 @@
<arg name="debug_view" default="true" doc="Specify whether the node displays a window to show debug image" />
<arg name="queue_size" default="3" doc="Specigy queue_size of input image subscribers" />

<arg name="morphology_ex_type" default="off" doc="off opening closing Specigy queue_size of input image subscribers" />
<arg name="morphology_ex_kernel_size" default="3" doc="opening closing Specigy queue_size of input image subscribers" />
<!-- <arg name="opening" default="true" doc="Morphological Transformations erosion followed by dilation." />
<arg name="closing" default="false" doc="Morphological Transformations Dilation followed by Erosion." /> -->

@@ -27,6 +29,8 @@
<param name="debug_view" value="$(arg debug_view)" />
<param name="queue_size" value="$(arg queue_size)" />

<param name="morphology_ex_type" value="$(arg morphology_ex_type)" />
<param name="morphology_ex_kernel_size" value="$(arg morphology_ex_kernel_size)" />
<!-- <param name="opening" value="$(arg opening)" />
<param name="closing" value="$(arg closing)" /> -->
<!-- <param name="canny_threshold" value="$(arg canny_threshold)" />
104 changes: 104 additions & 0 deletions launch/blob_detection_ims.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
<launch>
<arg name="node_name" default="blob_detection" />

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

<arg name="use_camera_info" default="false" doc="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." />
<arg name="debug_view" default="true" doc="Specify whether the node displays a window to show debug image" />
<arg name="queue_size" default="3" doc="Specigy queue_size of input image subscribers" />

<arg name="morphology_ex_type" default="off" doc="off opening closing Specigy queue_size of input image subscribers" />
<arg name="morphology_ex_kernel_size" default="3" doc="opening closing Specigy queue_size of input image subscribers" />
<!-- <arg name="running_mode" default="opencv_debug" doc="opencv_debug ros_dynamic_debug no_debug_view" /> -->
<arg name="running_mode" default="ros_dynamic_debug" doc="opencv_debug ros_dynamic_debug no_debug_view" />
<!-- <arg name="running_mode" default="no_debug_view" doc="opencv_debug ros_dynamic_debug no_debug_view" /> -->
<!-- <arg name="opening" default="true" doc="Morphological Transformations erosion followed by dilation." />
<arg name="closing" default="false" doc="Morphological Transformations Dilation followed by Erosion." /> -->

<!--
<arg name="lowHue" default="0" doc="lowHue." />
<arg name="highHue" default="179" doc="highHue" />
<arg name="lowSat" default="0" doc="lowSat" />
<arg name="highSat" default="255" doc="highSat" />
<arg name="lowVal" default="0" doc="lowVal" />
<arg name="highVal" default="255" doc="highVal" />
<arg name="max_circle_radius" default="0" doc="The maximum size of the circle, If unknown, put zero as default." /> -->
<group if="$(eval running_mode == 'opencv_debug')">
<!-- stuff that will only be evaluated if foo is true -->

<!-- blob_detection.cpp -->
<node name="$(arg node_name)" pkg="opencv_apps" type="blob_detection" output="screen">
<remap from="image" to="$(arg image)" />
<param name="use_camera_info" value="$(arg use_camera_info)" />
<param name="debug_view" value="true" />
<param name="queue_size" value="$(arg queue_size)" />

<param name="morphology_ex_type" value="$(arg morphology_ex_type)" />
<param name="morphology_ex_kernel_size" value="$(arg morphology_ex_kernel_size)" />
<!-- <param name="opening" value="$(arg opening)" />
<param name="closing" value="$(arg closing)" /> -->
<!-- <param name="canny_threshold" value="$(arg canny_threshold)" />
<param name="accumulator_threshold" value="$(arg accumulator_threshold)" />
<param name="gaussian_blur_size" value="$(arg gaussian_blur_size)" />
<param name="gaussian_sigma_x" value="$(arg gaussian_sigma_x)" />
<param name="gaussian_sigma_y" value="$(arg gaussian_sigma_y)" />
<param name="dp" value="$(arg dp)" />
<param name="min_circle_radius" value="$(arg min_circle_radius)" />
<param name="max_circle_radius" value="$(arg max_circle_radius)" /> -->
</node>

</group>

<group if="$(eval running_mode == 'ros_dynamic_debug')">

<!-- blob_detection.cpp -->
<node name="$(arg node_name)" pkg="opencv_apps" type="blob_detection" output="screen">
<remap from="image" to="$(arg image)" />
<param name="use_camera_info" value="$(arg use_camera_info)" />
<param name="debug_view" value="false" />
<param name="queue_size" value="$(arg queue_size)" />

<param name="morphology_ex_type" value="$(arg morphology_ex_type)" />
<param name="morphology_ex_kernel_size" value="$(arg morphology_ex_kernel_size)" />
<!-- <param name="opening" value="$(arg opening)" />
<param name="closing" value="$(arg closing)" /> -->
<!-- <param name="canny_threshold" value="$(arg canny_threshold)" />
<param name="accumulator_threshold" value="$(arg accumulator_threshold)" />
<param name="gaussian_blur_size" value="$(arg gaussian_blur_size)" />
<param name="gaussian_sigma_x" value="$(arg gaussian_sigma_x)" />
<param name="gaussian_sigma_y" value="$(arg gaussian_sigma_y)" />
<param name="dp" value="$(arg dp)" />
<param name="min_circle_radius" value="$(arg min_circle_radius)" />
<param name="max_circle_radius" value="$(arg max_circle_radius)" /> -->
</node>
<node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find opencv_apps)/config/blob_detection.rviz"/>

</group>

<group if="$(eval running_mode == 'no_debug_view')">

<!-- blob_detection.cpp -->
<node name="$(arg node_name)" pkg="opencv_apps" type="blob_detection" output="screen">
<remap from="image" to="$(arg image)" />
<param name="use_camera_info" value="$(arg use_camera_info)" />
<param name="debug_view" value="false" />
<param name="queue_size" value="$(arg queue_size)" />

<!-- <rosparam file="$(find opencv_apps)/config/blob_detection.yaml" /> -->
<rosparam file="$(find opencv_apps)/config/blob_detection_config.yaml" />

<!-- <param name="opening" value="$(arg opening)" />
<param name="closing" value="$(arg closing)" /> -->
<!-- <param name="canny_threshold" value="$(arg canny_threshold)" />
<param name="accumulator_threshold" value="$(arg accumulator_threshold)" />
<param name="gaussian_blur_size" value="$(arg gaussian_blur_size)" />
<param name="gaussian_sigma_x" value="$(arg gaussian_sigma_x)" />
<param name="gaussian_sigma_y" value="$(arg gaussian_sigma_y)" />
<param name="dp" value="$(arg dp)" />
<param name="min_circle_radius" value="$(arg min_circle_radius)" />
<param name="max_circle_radius" value="$(arg max_circle_radius)" /> -->
</node>
</group>

</launch>
55 changes: 55 additions & 0 deletions param/blob_detectio_testn.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
blobColor: 255
blobMsgType: Blob
debug_view: false
filterByArea: true
filterByCircularity: true
filterByColor: true
filterByConvexity: true
filterByInertia: true
highHue: 179.0
highSat: 255.0
highVal: 255.0
image:
compressed:
format: jpeg
jpeg_quality: 80
png_level: 9
compressedDepth:
depth_max: 10.0
depth_quantization: 100.0
png_level: 9
theora:
keyframe_frequency: 64
optimize_for: 1
quality: 31
target_bitrate: 800000
lowHue: 161.10000000000002
lowSat: 0.0
lowVal: 0.0
maxArea: 9000000
maxCircularity: 1.0
maxConvexity: 1.0
maxInertiaRatio: 1.0
minArea: 5000
minCircularity: 0.0
minConvexity: 0.0
minDistBetweenBlobs: 100
minInertiaRatio: 0.0
morphology_ex_kernel_size: 3
num_worker_threads: 1
queue_size: 3
thresholded_image:
compressed:
format: jpeg
jpeg_quality: 80
png_level: 9
compressedDepth:
depth_max: 10.0
depth_quantization: 100.0
png_level: 9
theora:
keyframe_frequency: 64
optimize_for: 1
quality: 31
target_bitrate: 800000
use_camera_info: false
144 changes: 86 additions & 58 deletions src/nodelet/blob_detection_nodelet.cpp
Original file line number Diff line number Diff line change
@@ -68,6 +68,9 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
{
image_transport::Publisher img_pub_;
image_transport::Publisher thresholded_img_pub_;
image_transport::Publisher thresholded_img_with_mask_pub_;
image_transport::Publisher morphology_ex_img_pub_;

image_transport::Subscriber img_sub_;
image_transport::CameraSubscriber cam_sub_;
ros::Publisher msg_pub_;
@@ -83,7 +86,7 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
bool debug_view_;
ros::Time prev_stamp_;

std::string window_name_, thresholded_image_name_, thresholded_image_with_mask_name_, blob_detector_params_name_, opening_image_name_, closing_image_name_; // reference to camshift_nodelet
std::string window_name_, thresholded_image_name_, thresholded_image_with_mask_name_, blob_detector_params_name_, morphology_ex_image_name_; // reference to camshift_nodelet
static bool need_config_update_;

cv::SimpleBlobDetector::Params params_; //
@@ -104,6 +107,9 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
int highVal;

std::string morphology_ex_type_;
std::string prev_morphology_ex_type_;
std::string morphology_ex_type_default_value_;
//char morphology_ex_type_;
int morphology_ex_kernel_size_;
int morphology_ex_kernel_size_initial_value_;

@@ -176,7 +182,6 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
return true;
}


void reconfigureCallback(Config& new_config, uint32_t level)
{
config_ = new_config;
@@ -189,7 +194,7 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
highVal = config_.highVal;

morphology_ex_kernel_size_ = config_.morphology_ex_kernel_size;

morphology_ex_type_ = config_.morphology_ex_type;
params_.filterByColor = config_.filterByColor;
params_.blobColor = config_.blobColor;

@@ -300,19 +305,34 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
cv::namedWindow(thresholded_image_name_, cv::WINDOW_AUTOSIZE);
cv::namedWindow(thresholded_image_with_mask_name_, cv::WINDOW_AUTOSIZE);
cv::namedWindow(blob_detector_params_name_, cv::WINDOW_AUTOSIZE);
if (morphology_ex_type_ == "opening")

if (morphology_ex_type_ != prev_morphology_ex_type_)
{
cv::namedWindow(opening_image_name_, cv::WINDOW_AUTOSIZE);
cv::createTrackbar("morphology_ex_kernel_size", opening_image_name_, &morphology_ex_kernel_size_, 100, trackbarCallback);
cv::destroyWindow(morphology_ex_image_name_);
morphology_ex_kernel_size_ = morphology_ex_kernel_size_initial_value_;
config_.morphology_ex_type = morphology_ex_type_;
config_.morphology_ex_kernel_size = morphology_ex_kernel_size_;
reconfigure_server_->updateConfig(config_);
}

else if (morphology_ex_type_ == "closing")
{
cv::namedWindow(closing_image_name_, cv::WINDOW_AUTOSIZE);
cv::createTrackbar("morphology_ex_kernel_size", closing_image_name_, &morphology_ex_kernel_size_, 100, trackbarCallback);
if (morphology_ex_type_ == "opening" || morphology_ex_type_ == "closing")
{
if (morphology_ex_type_ == "opening")
{
morphology_ex_image_name_ = "Opening Image";
}

else if (morphology_ex_type_ == "closing")
{
morphology_ex_image_name_ = "Closing Image";
}

cv::namedWindow(morphology_ex_image_name_, cv::WINDOW_AUTOSIZE);
cv::createTrackbar("morphology_ex_kernel_size", morphology_ex_image_name_, &morphology_ex_kernel_size_, 100, trackbarCallback);
}

prev_morphology_ex_type_ = morphology_ex_type_;

cv::createTrackbar("lowHue", thresholded_image_name_, &lowHue, 179, trackbarCallback);// should we increase the range? const int max_value_H = 360/2; https://docs.opencv.org/3.4/da/d97/tutorial_threshold_inRange.html
cv::createTrackbar("lowSat", thresholded_image_name_, &lowSat, 255, trackbarCallback);
cv::createTrackbar("lowVal", thresholded_image_name_, &lowVal, 255, trackbarCallback);
@@ -409,40 +429,36 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
//Point(morph_size, morph_size));

cv::Mat kernel;
cv::Mat opening_image;
cv::Mat closing_image;
cv::Mat morphology_ex_image;

if (morphology_ex_type_ == "opening")
{
if (morphology_ex_type_ == "opening" || morphology_ex_type_ == "closing")
{
if (morphology_ex_kernel_size_ % 2 != 1)
{
morphology_ex_kernel_size_ = morphology_ex_kernel_size_ + 1;
}

kernel = cv::getStructuringElement(cv::MORPH_RECT, cv::Size(morphology_ex_kernel_size_, morphology_ex_kernel_size_), cv::Point(-1, -1));

if (morphology_ex_type_ == "opening")
{
cv::morphologyEx(thresholded_image, morphology_ex_image, cv::MORPH_OPEN, kernel);
}

else if (morphology_ex_type_ == "closing")
{
cv::morphologyEx(thresholded_image, morphology_ex_image, cv::MORPH_CLOSE, kernel);
}
}

cv::morphologyEx(thresholded_image, opening_image, cv::MORPH_OPEN, kernel);
//morphologyEx(img, open, CV_MOP_OPEN, kernel);

//morphologyEx( src, dst, MORPH_TOPHAT, element, Point(-1,-1), i );
//morphologyEx( src, dst, MORPH_TOPHAT, element ); // here iteration=1
//MORPH_OPEN
}

else if (morphology_ex_type_ == "closing")
{
if (morphology_ex_kernel_size_ % 2 != 1)
{
morphology_ex_kernel_size_ = morphology_ex_kernel_size_ + 1;
}

kernel = cv::getStructuringElement(cv::MORPH_RECT, cv::Size(morphology_ex_kernel_size_, morphology_ex_kernel_size_), cv::Point(-1, -1));

//morphologyEx(img, close, CV_MOP_CLOSE, kernel);
//morphologyEx(image, output, MORPH_CLOSE, element,Point(-1, -1), 2);
cv::morphologyEx(thresholded_image, closing_image, cv::MORPH_CLOSE, kernel);
}

// Serena : not related to us, or later we use the same way to check on something if needed
// those paramaters cannot be =0
@@ -461,14 +477,9 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
// will hold the results of the detection
std::vector<cv::KeyPoint> keypoints;
// runs the actual detection
if (morphology_ex_type_ == "opening")
{
detector->detect(opening_image, keypoints);
}

else if (morphology_ex_type_ == "closing")
if (morphology_ex_type_ == "opening" || morphology_ex_type_ == "closing")
{
detector->detect(closing_image, keypoints);
detector->detect(morphology_ex_image, keypoints);
}

else
@@ -483,8 +494,6 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
std::cout << "test if there is keypoint detected : " << keypoints[0].size << std::endl;
}



// cv::Mat out_image;
// will we encounter this situation ?? if (frame.channels() == 1)
// {
@@ -523,14 +532,9 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
cv::imshow(thresholded_image_name_, thresholded_image);
cv::imshow(thresholded_image_with_mask_name_, thresholded_image_with_mask);

if (morphology_ex_type_ == "opening")
{
cv::imshow(opening_image_name_, opening_image);
}

else if (morphology_ex_type_ == "closing")
if (morphology_ex_type_ == "opening" || morphology_ex_type_ == "closing")
{
cv::imshow(closing_image_name_, closing_image);
cv::imshow(morphology_ex_image_name_, morphology_ex_image);
}

char c = (char)cv::waitKey(1);
@@ -541,32 +545,51 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
{
case 'o':
morphology_ex_type_ = "opening";
cv::destroyWindow(closing_image_name_);
morphology_ex_kernel_size_ = morphology_ex_kernel_size_initial_value_;
//morphology_ex_kernel_size_ = morphology_ex_kernel_size_initial_value_;
break;
case 'c':
morphology_ex_type_ = "closing";
cv::destroyWindow(opening_image_name_);
morphology_ex_kernel_size_ = morphology_ex_kernel_size_initial_value_;
//morphology_ex_kernel_size_ = morphology_ex_kernel_size_initial_value_;
break;
case 'n':
morphology_ex_type_ = "off";
cv::destroyWindow(opening_image_name_);
cv::destroyWindow(closing_image_name_);
morphology_ex_kernel_size_ = morphology_ex_kernel_size_initial_value_;
//morphology_ex_kernel_size_ = morphology_ex_kernel_size_initial_value_;
break;
}
}

if (thresholded_img_pub_.getNumSubscribers() > 0)
{
cv::Mat out_thresholded_image;
cv::cvtColor(thresholded_image, out_thresholded_image, cv::COLOR_GRAY2BGR);
sensor_msgs::Image::Ptr out_thresholded_img = cv_bridge::CvImage(msg->header, "bgr8", out_thresholded_image).toImageMsg();
thresholded_img_pub_.publish(out_thresholded_img);
}
// Publish the image.
// Publish the image.
cv::Mat out_thresholded_image;
cv::cvtColor(thresholded_image, out_thresholded_image, cv::COLOR_GRAY2BGR);

if (thresholded_img_with_mask_pub_.getNumSubscribers() > 0)
{
//cv::Mat out_thresholded_image_with_mask;
//cv::cvtColor(thresholded_image_with_mask, out_thresholded_image_with_mask, cv::COLOR_GRAY2BGR);
sensor_msgs::Image::Ptr out_thresholded_img_with_mask = cv_bridge::CvImage(msg->header, "bgr8", thresholded_image_with_mask).toImageMsg();
thresholded_img_with_mask_pub_.publish(out_thresholded_img_with_mask);
}

if (morphology_ex_img_pub_.getNumSubscribers() > 0)
{
if (morphology_ex_type_ == "opening" || morphology_ex_type_ == "closing")
{
cv::Mat out_morphology_ex_image;
cv::cvtColor(morphology_ex_image, out_morphology_ex_image, cv::COLOR_GRAY2BGR);
sensor_msgs::Image::Ptr out_morphology_ex_img = cv_bridge::CvImage(msg->header, "bgr8", out_morphology_ex_image).toImageMsg();
morphology_ex_img_pub_.publish(out_morphology_ex_img);
}
}

sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", out_image).toImageMsg();
sensor_msgs::Image::Ptr out_thresholded_img = cv_bridge::CvImage(msg->header, "bgr8", out_thresholded_image).toImageMsg();


img_pub_.publish(out_img);
thresholded_img_pub_.publish(out_thresholded_img);
msg_pub_.publish(blobs_msg); //s
}
catch (cv::Exception& e)
@@ -601,6 +624,7 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet

pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
pnh_->param("morphology_ex_type", morphology_ex_type_, morphology_ex_type_default_value_);

if (debug_view_)
{
@@ -611,12 +635,13 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet
window_name_ = "Blob Detection Demo";
thresholded_image_name_ = "Thresholded Image";
thresholded_image_with_mask_name_ = "Thresholded Image With Mask";
opening_image_name_ = "Opening Image";
closing_image_name_ = "Closing Image";
morphology_ex_image_name_ = "Opening Image";
blob_detector_params_name_ = "Blob Detector Params";
// delete output screen in launch file.
ROS_INFO("test for oninit.");

prev_morphology_ex_type_ = "off";
morphology_ex_type_default_value_ = "off";
morphology_ex_kernel_size_initial_value_ = 3;
max_minArea_ = 10000; // if 2560*1600 = 4096000
max_maxArea_ = 10000; // if 2560*1600 = 4096000
@@ -629,6 +654,9 @@ class BlobDetectionNodelet : public opencv_apps::Nodelet

img_pub_ = advertiseImage(*pnh_, "image", 1);
thresholded_img_pub_ = advertiseImage(*pnh_, "thresholded_image", 1);
thresholded_img_with_mask_pub_ = advertiseImage(*pnh_, "thresholded_image_with_mask", 1);
morphology_ex_img_pub_ = advertiseImage(*pnh_, "morphology_ex_image", 1);

msg_pub_ = advertise<opencv_apps::BlobArrayStamped>(*pnh_, "blobs", 1);

onInitPostProcess();