Hex demostrated in San Francisco
4 hours ago
| X | Y | R | Votes |
|---|---|---|---|
| ... | ... | ... | ... |
| 121 | 321 | 3 | 2 |
| 122 | 321 | 3 | 0 |
| 123 | 321 | 3 | 2 |
| 124 | 321 | 3 | 4 |
| 125 | 321 | 3 | 16 |
| ... | ... | ... | ... |
// strel_size is the size of the structuring element
cv::Size strel_size;
strel_size.width = 3;
strel_size.height = 3;
// Create an elliptical structuring element
cv::Mat strel = cv::getStructuringElement(cv::MORPH_ELLIPSE,strel_size);
// Apply an opening morphological operation using the structing element to the image twice
cv::morphologyEx(img_bin_,img_bin_,cv::MORPH_OPEN,strel,cv::Point(-1, -1),2);
// Convert White on Black to Black on White by inverting the image
cv::bitwise_not(img_bin_,img_bin_);
// Blur the image to improve detection
cv::GaussianBlur(img_bin_, img_bin_, cv::Size(7, 7), 2, 2 );
// See http://opencv.willowgarage.com/documentation/cpp/feature_detection.html?highlight=hough#HoughCircles
// The vector circles will hold the position and radius of the detected circles
cv::vector circles;
// Detect circles That have a radius between 20 and 400 that are a minimum of 70 pixels apart
cv::HoughCircles(img_bin_, circles, CV_HOUGH_GRADIENT, 1, 70, 140, 15, 20, 400 );
for( size_t i = 0; i < circles.size(); i++ )
{
// round the floats to an int
cv::Point center(cvRound(circles[i][0]), cvRound(circles[i][1]));
int radius = cvRound(circles[i][2]);
// draw the circle center
cv::circle( img_out_, center, 3, cv::Scalar(0,255,0), -1, 8, 0 );
// draw the circle outline
cv::circle( img_out_, center, radius+1, cv::Scalar(0,0,255), 2, 8, 0 );
// Debugging Output
ROS_INFO("x: %d y: %d r: %d",center.x,center.y, radius);
}
You can get the full version of the newest code by running roscd ihr_opencv && git pull origin master, or by starting at the beginning if you skipped that step. Once you have updated things the code can be built by running roscd ihr_opencv && rosmakeroslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/demo_hough.launchroslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/live_hough.launchroscd 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.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);
roscd ihr_opencv && rosmakeroslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/demo_morph.launchroslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/live_morph.launchvoid imageCallback (const sensor_msgs::ImageConstPtr & msg_ptr)
{
// Convert ROS Imput Image Message to IplImage
try
{
cv_input_ = bridge_.imgMsgToCv (msg_ptr, "bgr8");
}
catch (sensor_msgs::CvBridgeException error)
{
ROS_ERROR ("CvBridge Input Error");
}
// Convert IplImage to cv::Mat
img_in_ = cv::Mat (cv_input_).clone ();
// output = input
img_out_ = img_in_.clone ();
// Convert Input image from BGR to HSV
cv::cvtColor (img_in_, img_hsv_, CV_BGR2HSV);
// Zero Matrices
img_hue_ = cv::Mat::zeros(img_hsv_.rows, img_hsv_.cols, CV_8U);
img_sat_ = cv::Mat::zeros(img_hsv_.rows, img_hsv_.cols, CV_8U);
img_bin_ = cv::Mat::zeros(img_hsv_.rows, img_hsv_.cols, CV_8U);
// HSV Channel 0 -> img_hue_ & HSV Channel 1 -> img_sat_
int from_to[] = { 0,0, 1,1};
cv::Mat img_split[] = { img_hue_, img_sat_};
cv::mixChannels(&img_hsv_, 3,img_split,2,from_to,2);
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) > 128) {
img_bin_.at(i,j) = 255;
} else {
img_bin_.at(i,j) = 0;
// Clear pixel blue output channel
img_out_.at(i,j*3+0) = 0;
// Clear pixel green output channel
img_out_.at(i,j*3+1) = 0;
// Clear pixel red output channel
img_out_.at(i,j*3+2) = 0;
}
}
}
// Display Input image
cv::imshow ("input", img_in_);
// Display Binary Image
cv::imshow ("binary image", img_bin_);
// Display segmented image
cv::imshow ("segmented output", img_out_);
// Needed to keep the HighGUI window open
cv::waitKey (3);
}
roslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/demo_segment.launch
roslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/live_segment.launch
ihr_demo_hsv.cpp.
cd ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/src
int
main (int argc, char **argv)
{
// Initialize ROS Node
ros::init (argc, argv, "ihr_demo1");
// Start node and create a Node Handle
ros::NodeHandle nh;
// Instaniate Demo
Demo d (nh);
// Spin ...
ros::spin ();
// ... until done
return 0;
}
class Demo
{
protected:
ros::NodeHandle nh_;
image_transport::ImageTransport it_;
image_transport::Subscriber image_sub_;
sensor_msgs::CvBridge bridge_;
image_transport::Publisher image_pub_;
cv::Mat img_in_;
cv::Mat img_hsv_;
IplImage *cv_input_;
IplImage cv_output_;
...
};
public:
Demo (ros::NodeHandle & nh):nh_ (nh), it_ (nh_)
{
// Advertise image messages to a topic
image_pub_ = it_.advertise ("/demo/output_image", 1);
// Listen for image messages on a topic and setup callback
image_sub_ = it_.subscribe ("/usb_cam/image_raw", 1, &Demo::imageCallback, this);
// Open HighGUI Window
cv::namedWindow ("hsv", 1);
}
void imageCallback (const sensor_msgs::ImageConstPtr & msg_ptr)
{
// Convert ROS Imput Image Message to IplImage
try
{
cv_input_ = bridge_.imgMsgToCv (msg_ptr, "bgr8");
}
catch (sensor_msgs::CvBridgeException error)
{
ROS_ERROR ("CvBridge Input Error");
}
// Convert IplImage to cv::Mat
img_in_ = cv::Mat (cv_input_).clone ();
// Convert Input image from BGR to HSV
cv::cvtColor (img_in_, img_hsv_, CV_BGR2HSV);
// Display HSV Image in HighGUI window
cv::imshow ("hsv", img_hsv_);
// Needed to keep the HighGUI window open
cv::waitKey (3);
// Convert cv::Mat to IplImage
cv_output_ = img_hsv_;
// Convert IplImage to ROS Output Image Message and Publish
try
{
image_pub_.publish (bridge_.cvToImgMsg (&cv_output_, "bgr8"));
}
catch (sensor_msgs::CvBridgeException error)
{
ROS_ERROR ("CvBridge Output error");
}
}
cd ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv
rosdep install ihr_opencv
rosmake ihr_opencv
roslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/demo_hsv.launch
roslaunch ~/ros/stacks/iheart-ros-pkg/ihr_demos/ihr_opencv/launch/live_hsv.launch