Tutorial: How to use ROS grabber

Introduction

ViSP library allows to grab images from cameras using specific classes depending on the underlaying camera drivers. Thus it allows to grab images from firewire or usb cameras using either vp1394TwoGrabber or vpV4l2Grabber classes.

In the next section Image grabbing using ViSP, we recall how ViSP can be used to grab images. Then in section How to grab images from ROS we introduce vpROSGrabber that can be used to grab images published by a ROS camera node.

Image grabbing using ViSP

Working with firewire cameras

Let us consider the following classical ViSP example provided in tutorial-visp-grabber-1394.cpp and given here after. Thanks to the vp1394TwoGrabber class provided in ViSP library we are able to grab images from a firewire camera.

#include <visp/vp1394TwoGrabber.h>
#include <visp/vpDisplayX.h>
#include <visp/vpImage.h>
int
{
#ifdef VISP_HAVE_DC1394_2
try
{
vpImage< unsigned char > I; // Create a gray level image container
bool reset = true; // Enable bus reset during construction (default)
vp1394TwoGrabber g( reset ); // Create a grabber based on libdc1394-2.x third party lib
g.setVideoMode( vp1394TwoGrabber::vpVIDEO_MODE_640x480_MONO8 );
g.setFramerate( vp1394TwoGrabber::vpFRAMERATE_60 );
g.open( I );
std::cout << "Image size: " << I.getWidth() << " " << I.getHeight() << std::endl;
#ifdef VISP_HAVE_X11
vpDisplayX d( I );
#else
std::cout << "No image viewer is available..." << std::endl;
#endif
while ( 1 )
{
g.acquire( I );
vpDisplay::display( I );
vpDisplay::flush( I );
if ( vpDisplay::getClick( I, false ) )
break;
}
}
catch ( vpException e )
{
std::cout << "Catch an exception: " << e << std::endl;
}
#endif
}

This example is described in ViSP image frame grabbing tutorial pages.

To build this example ViSP should be installed. If not, depending on your ROS distro it could be done like:

sudo apt-get install ros-<distro>-visp

ViSP could also be installed from Debian package:

sudo apt-get install libvisp-dev

Now to build this example, just run the following commands in a terminal:

cd ~/catkin_ws/src/visp_ros/tutorial/grabber/visp
cmake .
make

To run this example, connect a firewire camera hit in the same terminal:

./tutorial-visp-grabber-1394

Working with usb cameras

Let us consider this other ViSP example provided in tutorial-visp-grabber-v4l2.cpp and given here after. Thanks to the vpV4l2Grabber class we are able this time to grab images from an usb camera.

#include <visp/vpDisplayX.h>
#include <visp/vpImage.h>
#include <visp/vpV4l2Grabber.h>
int
{
#ifdef VISP_HAVE_V4L2
try
{
vpImage< unsigned char > I;
vpV4l2Grabber g;
g.open( I );
std::cout << "Image size: " << I.getWidth() << " " << I.getHeight() << std::endl;
#ifdef VISP_HAVE_X11
vpDisplayX d( I );
#else
std::cout << "No image viewer is available..." << std::endl;
#endif
while ( 1 )
{
g.acquire( I );
vpDisplay::display( I );
vpDisplay::flush( I );
if ( vpDisplay::getClick( I, false ) )
break;
}
}
catch ( vpException e )
{
std::cout << "Catch an exception: " << e << std::endl;
}
#endif
}

To run this example, connect an usb camera and hit in the same terminal:

./tutorial-visp-grabber-v4l2

Conclusion

Depending on the camera that is used, you may adapt your code to use the right camera driver. This may be fastidious. That is why, in the next section we show how to use a more generic grabber class based on ROS and called vpROSGrabber. It just subscribes to a camera topic.

How to grab images from ROS

visp_ros package provides vpROSGrabber class that is able to handle any images published on a ROS topic. This class is interesting since it can be used as a classical ViSP class without knowing ROS very well since it makes ROS transparent for the user.

To be able to grab images published by a ROS camera node and display these images, the previous example need to be modified as in tutorial-ros-grabber.cpp given below:

#include <visp/vpDisplayX.h>
#include <visp/vpImage.h>
int
main( int argc, const char **argv )
{
try
{
bool opt_use_camera_info = false;
for ( int i = 0; i < argc; i++ )
{
if ( std::string( argv[i] ) == "--use-camera-info" )
opt_use_camera_info = true;
else if ( std::string( argv[i] ) == "--help" )
{
std::cout << "Usage: " << argv[0] << " [--use-camera-info] [--help]" << std::endl;
return 0;
}
}
std::cout << "Use camera info: " << ( ( opt_use_camera_info == true ) ? "yes" : "no" ) << std::endl;
// vpImage<unsigned char> I; // Create a gray level image container
vpImage< vpRGBa > I; // Create a color image container
vpROSGrabber g; // Create a grabber based on ROS
g.setImageTopic( "/camera/image_raw" );
if ( opt_use_camera_info )
{
g.setCameraInfoTopic( "/camera/camera_info" );
g.setRectify( true );
}
g.open( I );
std::cout << "Image size: " << I.getWidth() << " " << I.getHeight() << std::endl;
#ifdef VISP_HAVE_X11
vpDisplayX d( I );
#else
std::cout << "No image viewer is available..." << std::endl;
#endif
while ( 1 )
{
g.acquire( I );
vpDisplay::display( I );
vpDisplay::displayText( I, 20, 20, "A click to quit...", vpColor::red );
vpDisplay::flush( I );
if ( vpDisplay::getClick( I, false ) )
break;
}
}
catch ( vpException e )
{
std::cout << "Catch an exception: " << e << std::endl;
}
}

Compared to the example based fully on ViSP and given in the Image grabbing using ViSP, once declared :

vpROSGrabber g; // Create a grabber based on ROS

we simply indicate which is the image topic name:

g.setImageTopic( "/camera/image_raw" );

If camera_info parameters are provided including distorsion, the image is rectified:

if ( opt_use_camera_info )
{
g.setCameraInfoTopic( "/camera/camera_info" );
g.setRectify( true );
}

Next as usual with ViSP, the device is opened

g.open( I );

and a new image is acquired using:

g.acquire( I );

Now to build this example, install visp_ros catkin package and setup the environment as described in the tutorial: Howto build and install visp_ros.

source ~/catkin_ws/install/setup.bash

Build the example by entering the following commands in a terminal:

cd ~/catkin_ws/src/visp_ros/tutorial/grabber/ros
cmake .
make

Working with firewire cameras

The previous example can work with images published by camera1394 node. To this end let us consider the following launch file named "camera-firewire.launch" where images are published on topic /camera/image_raw and camera parameters on topic /camera/camera_info.

Note
The camera parameters are read from cam_parameters.yml file provided with the source code.
<launch>
<!-- Launch the firewire camera acquisition node -->
<node pkg="camera1394" type="camera1394_node" name="my_camera1394_node" args="_video_mode:=640x480_rgb8" >
<param name="camera_info_url" value="package://visp_ros/tutorial/grabber/ros/cam_parameters.yml" />
</node>
</launch>

When launched, you will see the images:

cd ~/catkin_ws/src/visp_ros/tutorial/grabber/ros
roslaunch camera-firewire.launch
./tutorial-ros-grabber --use-camera-info

Working with usb cameras

The previous example can also work with images published by usb_cam node. To this end let us consider the following launch file named "camera-usb.launch" where images are published on topic /camera/image_raw and camera parameters on topic /camera/camera_info.

<launch>
<!-- % rosrun usb_cam usb_cam_node _video_device:="/dev/video0" _pixel_format:="yuyv" _io_method:="mmap" _image_height:=640 _image_height:=480 -->
<node pkg="usb_cam" type="usb_cam_node" name="camera" output="screen" >
<param name="video_device" value="/dev/video0" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="io_method" value="mmap"/>
<param name="camera_info_url" value="package://visp_ros/tutorial/grabber/ros/cam_parameters.yml" />
</node>
</launch>

When launched, you will see the images:

cd ~/catkin_ws/src/visp_ros/tutorial/grabber/ros
roslaunch camera-usb.launch --use-camera-info
./tutorial-ros-grabber
usb_cam
vpROSGrabber
Class for cameras video capture for ROS cameras.
Definition: vpROSGrabber.h:104
main
int main(int argc, char **argv)
Definition: afma6.cpp:187
vpROSGrabber::open
void open(int argc, char **argv)
Definition: vpROSGrabber.cpp:98
d
d
vpROSGrabber::setImageTopic
void setImageTopic(const std::string &topic_name)
Definition: vpROSGrabber.cpp:592
vpROSGrabber::setCameraInfoTopic
void setCameraInfoTopic(const std::string &topic_name)
Definition: vpROSGrabber.cpp:579
param
T param(const std::string &param_name, const T &default_val)
vpROSGrabber::acquire
void acquire(vpImage< unsigned char > &I)
Definition: vpROSGrabber.cpp:412
args
vpROSGrabber::setRectify
void setRectify(bool rectify)
Definition: vpROSGrabber.cpp:517
vpROSGrabber.h
class for Camera video capture for ROS middleware.


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33