roscd ihr_opencv && git pull origin master
should download the latest examples. If you haven't installed the example code already you may want to start at the beginning.Morphological operations can be performed on images to improve the recognition of desirable features and remove undesired features such as noise. In this case we want to remove noise from the image so we will perform a morphological open which is an erode operation followed by a dilate operation.
To perform these operations first we need to construct a structuring element. The structuring element is an MxN matrix containing binary values that will be used to modify each element in the original image. OpenCV has functions to automatically generate rectangular, elliptical, and cross shaped structuring elements. In general the structuring elements can have any shape but these are the most common and useful for most applications. The image below shows from left to right: a 5x3 rectangular element, a 5x5 elliptical element and a 5x5 cross element.
The structuring element is then used to compare the values of each element and its neighbors. An erode operation with a 3x3 cross element will set the output pixel to a 1 if the input pixel is a 1 and the pixels above, below, and the the left and right are all also 1.
The dilate operation shown below is the inverse of the erode operation. In the case of a 3x3 cross element the output pixel and the pixels above, below and to the left and right will all be set to 1 if the input is a 1.
The open operation is an erode followed by a dilate whereas the clode operation is a dilate followed by an erode. There are many more morphological operations that can be performed to improve the quality of the image, however in this program we will only be using the open operation.
After segmenting the image by hue and converting it into a binary image we are then able to remove noise from the image using an open operation which is applied three times in a row. This is effectively the same as setting the
output = dilate(dilate(dilate(erode(erode(erode(input)))))).
for(int i = 0; i < img_out_.rows; i++) { for(int j = 0; j < img_out_.cols; j++) { // The output pixel is white if the input pixel // hue is orange and saturation is reasonable if(img_hue_.at(i,j) > 4 && img_hue_.at (i,j) < 28 && img_sat_.at (i,j) > 96) { img_bin_.at (i,j) = 255; } else { img_bin_.at (i,j) = 0; } } } cv::Size strel_size; strel_size.width = 3; strel_size.height = 3; cv::Mat strel = cv::getStructuringElement(cv::MORPH_ELLIPSE,strel_size); cv::morphologyEx(img_bin_,img_out_,cv::MORPH_OPEN,strel,cv::Point(-1, -1),3);
The code can be built by running
roscd ihr_opencv && rosmake
This demo can be run using the prerecorded .bag file
roslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/demo_morph.launch
If you have an orange and a webcam you can try this at home with the live version.
roslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/live_morph.launch
In the next episode, we will cover the use of the Hough transform to detect the circular outline of the test oranges giving us the location of the center and the radius.
No comments:
Post a Comment