The goal of this tutorial is to get you up and running with ROS (Robot Operating System) environment and open source computer vision library OpenCV as fast as possible.
My environment
- Ubuntu 11.04
- ROS Diamondback Desktop Full installed. For instructions on how to install ROS, please refer to: http://www.ros.org/wiki/diamondback/Installation/Ubuntu
- Logitech QuickCam Pro 9000 Web camera
ROS supports many camera drivers which let us control the camera parameters like resolution, frame rate etc., and publish raw images for further processing by the code. Here, i will be using uvc_cam USB camera driver written by Eric Perko.
We will:
- Launch the uvc_cam driver to start publishing the images.
- Subscribe to these images using image_transport
- Convert the images from ROS image message format to OpenCV image format using cv_bridge
- Process them using OpenCV commands
- Convert the images from OpenCV image message format to ROS image message using cv_bridge
- Publish the processed images using image_transport
Software for Testing Webcam
Before moving ahead, it is important to make sure whether your webcam works or not in linux. There are some open-source programs like:
- Cheeseuses the gstreamer library, which utlilizes the video4linux2 API to capture video and stills from a webcam. It can also apply some special effects. Type
$ sudo apt-get install cheese
to install it.
- GUVCView is a graphical front-end for UVC drivers built using GTK+. It is way better than cheesefor controlling webcam and recording audio/video. Type
$ sudo apt-get install guvcview
to install it.
Install Camera Drivers to work with ROS
- Open the terminal window, go to the directory where you would like to install the camera driver package. In my computer, I installed it in the home directory (go there by typing cd in the terminal window).
- Download the uvc_campackage:
$ git clone https://github.com/ericperko/uvc_cam.git
This will create a directory called uvc_cam.
- In order to compile and make/build this package you would need elevated permissions. Type:
$ sudo bash
and then enter the password. You should now have root access.
- Before making the package you need to tell ROS where to find it. Type:
# cd # gedit .bashrc
A text editor should open up. Next add the following line at the end:
export ROS_PACKAGE_PATH=~/uvc_cam:$ROS_PACKAGE_PATH
Save and Exit the text editor.
- Restart the terminal, get root access again and type:
# rosmake --rosdep-install uvc_cam
In the rosmake results you should notice:
[ rosmake ] Results: [ rosmake ] Built 49 packages with 0 failures.
If you notice some failures, you may not have root access.
Find which device is the camera connected to.
- Open Terminal Window
- Disconnect the camera from the computer and type the following in the terminal:
$ ls /dev/video*
If you dont have any other cameras connected to your computer you would see no output, else you would see something like
/dev/video0
Remember the number of devices listed in this step.
- Now connect the camera to your computer and repeat step 2. You should see a new device added to the list like:
/dev/video0
So, the camera is connected to /dev/video0. We will used this information in the next section.
Create a new package for image processing
- Open a new terminal window and in the home directory, type the following:
$ roscreate-pkg tutorialROSOpenCV image_transport roscpp std_msgs opencv2 cv_bridge uvc_cam
This will create a new directory called tutorialROSOpenCV.
- We will now create a launch directory where we would store the file used to launch the uvc_camnode in order for it to start publishing the images. Change directory:
$ cd tutorialROSOpenCV
Now make a new directory under it called launch:
$ mkdir launch
This is where we will store the launch file.
- Change directory:
$ cd launch
Create the new launch file by typing:
$ gedit uvcCamLaunch.launch
Paste the following in there:
<launch> <node name="uvc_cam_node" pkg="uvc_cam" type="uvc_cam_node" output="screen"> <param name="device" value="/dev/video0" /> <param name="width" value="320" /> <param name="height" value="240" /> <param name="frame_rate" value="20" /> </node> </launch>Save and exit. Notice the parameter device with value: /dev/video0. Change this to the actual device path. Refer to previous section.
- Before making this package you need to tell ROS where to find it. Gain root access in the terminal and type:
# cd # gedit .bashrc
A text editor should open up. Next add the following line at the end:
export ROS_PACKAGE_PATH=~/tutorialROSOpenCV:$ROS_PACKAGE_PATH
Save and Exit the text editor.
- Restart the terminal, gain root access, and type:
# rosmake tutorialROSOpenCV
In the rosmake results you should notice:
[ rosmake ] Results: [ rosmake ] Built 50 packages with 0 failures.
If you notice some failures, you may not have root access.
Test the Launch script
In order to make sure that the package uvc_cam is in fact publishing the images, we will now run the node and check the output.
- In a new terminal type:
$ roslaunch tutorialROSOpenCV uvcCamLaunch.launch
If your webcam has an integrated light indicator, you should see it light up.
- Now we will make sure that the images are being published. Open up another terminal window and type:
$ rostopic list
You should see the following topics being published:
/camera/camera_info /camera/image_raw /camera/image_raw/compressed /camera/image_raw/compressed/parameter_descriptions /camera/image_raw/compressed/parameter_updates /camera/image_raw/theora /camera/image_raw/theora/parameter_descriptions /camera/image_raw/theora/parameter_updates /rosout /rosout_agg /uvc_cam_node/parameter_descriptions /uvc_cam_node/parameter_updates
- Lets look at the topic /camera/image_raw. Type:
$ rosrun image_view image_view image:=/camera/image_raw
You should see a new window pop-up with a continuous streaming video capture output of the webcam. Press Ctrl-Cto exit. Lets look at the format of this topic. Type
$ rostopic info /camera/image_raw
You should see something like this:
Type: sensor_msgs/Image Publishers: * /uvc_cam_node (http://username-computername:port/) Subscribers: None
sensor_msgs/Image is a ROS image format which contains the header, height, width, step, and image data. Refer to: http://www.ros.org/doc/api/sensor_msgs/html/msg/Image.html for more information.
- Lets look at the topic /camera/camera_info. Type:
$ rostopic info /camera/camera_info
You should see something like this:
Type: sensor_msgs/CameraInfo Publishers: * /uvc_cam_node (http://username-computername:port/) Subscribers: None
sensor_msgs/CameraInfo is a ROS information format which contains the header, height, width, distortion model params, binning params and ROI (region of interest) params. Refer to: http://www.ros.org/doc/api/sensor_msgs/html/msg/CameraInfo.htmlfor more info. You can view the contents of this topic by typing:
rostopic echo -c /camera/camera_info
Write the code for image processing
- In a new terminal window, type the following:
$ roscd tutorialROSOpenCV/src
We will now create the source file which will contain the code. Type:
$ gedit main.cpp
The following program inverts the colors of the image captured from the webcam. Paste the following code in the file:
//Includes all the headers necessary to use the most common public pieces of the ROS system. #include <ros/ros.h> //Use image_transport for publishing and subscribing to images in ROS #include <image_transport/image_transport.h> //Use cv_bridge to convert between ROS and OpenCV Image formats #include <cv_bridge/cv_bridge.h> //Include some useful constants for image encoding. Refer to: http://www.ros.org/doc/api/sensor_msgs/html/namespacesensor__msgs_1_1image__encodings.html for more info. #include <sensor_msgs/image_encodings.h> //Include headers for OpenCV Image processing #include <opencv2/imgproc/imgproc.hpp> //Include headers for OpenCV GUI handling #include <opencv2/highgui/highgui.hpp> //Store all constants for image encodings in the enc namespace to be used later. namespace enc = sensor_msgs::image_encodings; //Declare a string with the name of the window that we will create using OpenCV where processed images will be displayed. static const char WINDOW[] = "Image Processed"; //Use method of ImageTransport to create image publisher image_transport::Publisher pub; //This function is called everytime a new image is published void imageCallback(const sensor_msgs::ImageConstPtr& original_image) { //Convert from the ROS image message to a CvImage suitable for working with OpenCV for processing cv_bridge::CvImagePtr cv_ptr; try { //Always copy, returning a mutable CvImage //OpenCV expects color images to use BGR channel order. cv_ptr = cv_bridge::toCvCopy(original_image, enc::BGR8); } catch (cv_bridge::Exception& e) { //if there is an error during conversion, display it ROS_ERROR("tutorialROSOpenCV::main.cpp::cv_bridge exception: %s", e.what()); return; } //Invert Image //Go through all the rows for(int i=0; i<cv_ptr->image.rows; i++) { //Go through all the columns for(int j=0; j<cv_ptr->image.cols; j++) { //Go through all the channels (b, g, r) for(int k=0; k<cv_ptr->image.channels(); k++) { //Invert the image by subtracting image data from 255 cv_ptr->image.data[i*cv_ptr->image.rows*4+j*3 + k] = 255-cv_ptr->image.data[i*cv_ptr->image.rows*4+j*3 + k]; } } } //Display the image using OpenCV cv::imshow(WINDOW, cv_ptr->image); //Add some delay in miliseconds. The function only works if there is at least one HighGUI window created and the window is active. If there are several HighGUI windows, any of them can be active. cv::waitKey(3); /** * The publish() function is how you send messages. The parameter * is the message object. The type of this object must agree with the type * given as a template parameter to the advertise<>() call, as was done * in the constructor in main(). */ //Convert the CvImage to a ROS image message and publish it on the "camera/image_processed" topic. pub.publish(cv_ptr->toImageMsg()); } /** * This tutorial demonstrates simple image conversion between ROS image message and OpenCV formats and image processing */ int main(int argc, char **argv) { /** * The ros::init() function needs to see argc and argv so that it can perform * any ROS arguments and name remapping that were provided at the command line. For programmatic * remappings you can use a different version of init() which takes remappings * directly, but for most command-line programs, passing argc and argv is the easiest * way to do it. The third argument to init() is the name of the node. Node names must be unique in a running system. * The name used here must be a base name, ie. it cannot have a / in it. * You must call one of the versions of ros::init() before using any other * part of the ROS system. */ ros::init(argc, argv, "image_processor"); /** * NodeHandle is the main access point to communications with the ROS system. * The first NodeHandle constructed will fully initialize this node, and the last * NodeHandle destructed will close down the node. */ ros::NodeHandle nh; //Create an ImageTransport instance, initializing it with our NodeHandle. image_transport::ImageTransport it(nh); //OpenCV HighGUI call to create a display window on start-up. cv::namedWindow(WINDOW, CV_WINDOW_AUTOSIZE); /** * Subscribe to the "camera/image_raw" base topic. The actual ROS topic subscribed to depends on which transport is used. * In the default case, "raw" transport, the topic is in fact "camera/image_raw" with type sensor_msgs/Image. ROS will call * the "imageCallback" function whenever a new image arrives. The 2nd argument is the queue size. * subscribe() returns an image_transport::Subscriber object, that you must hold on to until you want to unsubscribe. * When the Subscriber object is destructed, it will automatically unsubscribe from the "camera/image_raw" base topic. */ image_transport::Subscriber sub = it.subscribe("camera/image_raw", 1, imageCallback); //OpenCV HighGUI call to destroy a display window on shut-down. cv::destroyWindow(WINDOW); /** * The advertise() function is how you tell ROS that you want to * publish on a given topic name. This invokes a call to the ROS * master node, which keeps a registry of who is publishing and who * is subscribing. After this advertise() call is made, the master * node will notify anyone who is trying to subscribe to this topic name, * and they will in turn negotiate a peer-to-peer connection with this * node. advertise() returns a Publisher object which allows you to * publish messages on that topic through a call to publish(). Once * all copies of the returned Publisher object are destroyed, the topic * will be automatically unadvertised. * * The second parameter to advertise() is the size of the message queue * used for publishing messages. If messages are published more quickly * than we can send them, the number here specifies how many messages to * buffer up before throwing some away. */ pub = it.advertise("camera/image_processed", 1); /** * In this application all user callbacks will be called from within the ros::spin() call. * ros::spin() will not return until the node has been shutdown, either through a call * to ros::shutdown() or a Ctrl-C. */ ros::spin(); //ROS_INFO is the replacement for printf/cout. ROS_INFO("tutorialROSOpenCV::main.cpp::No error."); }Save and Exit.
- Before we make the program, we have to edit the CMakeLists.txtfile to ensure it will build and make an executable file of the program above. Gain root access, and type:
# roscd tutorialROSOpenCV/
Then we will edit the CMakeLists file. Type:
# gedit CMakeLists.txt
At the end of the file add the following line:
rosbuild_add_executable(tutorialROSOpenCV src/main.cpp)
Save and Exit.
- Now we can compile/make the package. Type:
# rosmake tutorialROSOpenCV
You should notice the following:
[ rosmake ] Results: [ rosmake ] Built 50 packages with 0 failures. [ rosmake ] Summary output to directory
- To run the project, type:
# rosrun tutorialROSOpenCV tutorialROSOpenCV
You should see a window being created titled Image Processed containing the inverted image from the webcam
- In order to ensure that the processed image has been published as a rostopic, in a new terminal window type:
# rostopic list
You would see the following:
/camera/camera_info /camera/image_processed /camera/image_processed/compressed /camera/image_processed/compressed/parameter_descriptions /camera/image_processed/compressed/parameter_updates /camera/image_processed/theora /camera/image_processed/theora/parameter_descriptions /camera/image_processed/theora/parameter_updates /camera/image_raw /camera/image_raw/compressed /camera/image_raw/compressed/parameter_descriptions /camera/image_raw/compressed/parameter_updates /camera/image_raw/theora /camera/image_raw/theora/parameter_descriptions /camera/image_raw/theora/parameter_updates /rosout /rosout_agg /uvc_cam_node/parameter_descriptions /uvc_cam_node/parameter_updates
To check the image data in rostopic /camera/image_processed, type:
$ rosrun image_view image_view image:=/camera/image_processed
You should see a new window pop-up with a continuous streaming video capture output of the webcam with image inverted. Press Ctrl-C to exit.































































