User Tools

Site Tools


ardrone_detect_blue

This is an old revision of the document!


Detecting Blue Color

=Introduction= This tutorial you will learn to write an other simple program for filtering blue colored objects.In tutorial “How to make ROS and Opencv work together” you would have created a package called “roscv” if you have not done that please follow that tutorial. Another prerequisite for this tutorial is the ardrone. I have given directions in the first tutorial on how to connect your computer to the ardrone.

Add an other source file

step 1:Go to folder named “src” in the package “roscv”and create a file called “bluetrack.cpp”

step 2: In the empty file and paste the following code and after that save the file.

<source lang=“C”>

#include <ros/ros.h> #include <stdio.h> #include <iostream> #include “std_msgs/String.h” #include <image_transport/image_transport.h> #include <cv_bridge/cv_bridge.h> #include <sensor_msgs/image_encodings.h> #include <opencv2/imgproc/imgproc.hpp> make sure to include the relevant headerfiles #include <opencv2/highgui/highgui.hpp> #include <opencv/cv.h> #include <opencv/highgui.h> #include <cv_bridge/CvBridge.h> #include <cvaux.h> #include<math.h> #include <cxcore.h> #include “turtlesim/Velocity.h” #include <turtlesim/Pose.h> #include <highgui.h> using namespace std; using namespace cv; namespace enc = sensor_msgs::image_encodings; static double r=0,g=0,b=0; static const char WINDOW[] = “Image window”; class ImageConverter { ros::NodeHandle nh_; ros::NodeHandle n; ros::Publisher pub ; image_transport::ImageTransport it_; image_transport::Subscriber image_sub_; image subscriber

image_transport::Publisher image_pub_; //image publisher(we subscribe to ardrone image_raw)
std_msgs::String msg;

public: ImageConverter()

  : it_(nh_)
{
    
    pub= n.advertise<turtlesim::Pose>("/drone/walldis", 500);
    image_sub_ = it_.subscribe("/ardrone/image_raw", 1, &ImageConverter::imageCb, this);
   image_pub_= it_.advertise("/arcv/Image",1);
    
   }
~ImageConverter()
{
  cv::destroyWindow(WINDOW);
}
void imageCb(const sensor_msgs::ImageConstPtr& msg)
{
  
   sensor_msgs::CvBridge bridge;//we need this object bridge for facilitating conversion from ros-img to opencv
   IplImage* img = bridge.imgMsgToCv(msg,"bgr8");  //image being converrosbuild_add_executableted from ros to opencv using cvbridge

IplImage* img1 = cvCreateImage( cvGetSize(img), IPL_DEPTH_8U, 3 ); IplImage* imgThreshedred = cvCreateImage(cvGetSize(img), IPL_DEPTH_8U, 1); IplImage* imgThreshedgreen = cvCreateImage(cvGetSize(img), IPL_DEPTH_8U, 1); IplImage* imgThreshedblue = cvCreateImage(cvGetSize(img), IPL_DEPTH_8U, 1); IplImage* imgThreshedminus = cvCreateImage(cvGetSize(img), IPL_DEPTH_8U, 1); cvSplit(img, imgThreshedblue, imgThreshedgreen, imgThreshedred, NULL); cvSub(imgThreshedblue,imgThreshedgreen,imgThreshedminus,0); cvSub(imgThreshedminus,imgThreshedred,imgThreshedminus,0);

cvInRangeS(imgThreshedred, cvScalar(254), cvScalar(255), imgThreshedINrange); cvShowImage( “imgTHRESHOLDminus”,imgThreshedminus); cvShowImage( “IMG”,img);

cvWaitKey(2);   

} };

int main(int argc, char** argv) {

ros::init(argc, argv, "image_converter");
ImageConverter ic;
ros::spin();

return 0; } </source>

Make changes in the CMakeLists.txt

Step 1: Open up the file named “CMakeLists.txt” and search for the lines beginning with “rosbuild_add_executable”. In that add the file you created which is “bluetrack.cpp”. Save and close the file.

Test the code

Step 1: While you are at the folder of the package “roscv”. Open up a terminal and enter

cmake . <br> After that enter <br>

rosmake <br> Make sure rosmake gets you “0” failures.

Step 2: Turn on the ARDRONE and connect to it using WiFi.Now enter the following commands one after the other : <br> <br> <pre> roscore

rosrun ardrone_brown ardrone_driver

rosrun roscv roscv </pre>

<br><br>

You should be getting two windows. I used a blue cup for detecting and the here is a picture of that.

ros and opencv

after filter

ardrone_detect_blue.1478023424.txt.gz · Last modified: 2016/11/01 11:03 by dwallace