Adding Video Capture in ROS
Video with RVIZ #
In this tutorial, you will learn in detail how to configure your own RVIZ session to see only the video data that you require.
To visualize the video stream published by the ZED node, you can use two different plugins:
Camera
: Displays an image from a camera, with the visualized world rendered behind itImage
: Displays an image from a topic of typesensor_msgs/Image
Camera #
The Camera
plugin allows you to visualize an image from a topic of type sensor_msgs/Image
. It acts as if the source of the image is placed on its virtual frame and renders all virtual objects in front of it.
Key parameters:
Image topic
: Selects the image topic to visualize from the list of available images in the combo boxTransport hint
: Selects the type of compression from the list. Using a compressed image allows reducing the required bandwidth if the image is transmitted to another machine over the ROS networkQueue size
: The size of the message queue. Use a lower value to reduce latencyUnreliable
: Enables using the UDP network protocol instead of the default TCP protocol in order to reduce latency
By expanding Visibility
, you can select/deselect what will be visible in the camera view
. Only active plugins can be selected.
Image #
The Image
plugin allows you to visualize an image from a topic of type sensor_msgs/Image
.
Key parameters:
Image topic
: Selects the image topic to visualize from the list of available images in the combo boxTransport hint
: Selects the type of compression from the list. Using a compressed image allows reducing the required bandwidth if the image is transmitted to another machine over the ROS networkQueue size
: The size of the message queue. Use a lower value to reduce latencyUnreliable
: Enables using the UDP network protocol instead of the default TCP protocol in order to reduce latency
Video subscribing in C++ #
In this tutorial, you will learn how to write a simple C++ node that subscribes to messages of type
sensor_msgs/Image
. This lets you retrieve the Left and Right rectified images published by the ZED node.
Introduction #
Use this command to connect the ZED camera to the ROS network:
- ZED:
$ roslaunch zed_wrapper zed.launch
- ZED-M:
$ roslaunch zed_wrapper zedm.launch
- ZED2:
$ roslaunch zed_wrapper zed2.launch
- ZED2i:
$ roslaunch zed_wrapper zed2i.launch
The ZED node will start to publish image data in the network only if there is another node that subscribes to the relative topic.
Running the tutorial #
If you properly followed the ROS Installation Guide, the executable of this tutorial has been compiled and you can run the subscriber node using this command:
$ rosrun zed_video_sub_tutorial zed_video_sub
If the ZED node is running and a camera is connected or you have loaded an SVO file, you will receive the following stream of messages confirming that you have correctly subscribed to the ZED image topics:
[ INFO] [1536328544.086771765]: Left Rectified image received from ZED - Size: 1280x720
[ INFO] [1536328544.089849129]: Right Rectified image received from ZED - Size: 1280x720
[ INFO] [1536328544.097859387]: Left Rectified image received from ZED - Size: 1280x720
[ INFO] [1536328544.100533804]: Right Rectified image received from ZED - Size: 1280x720
[ INFO] [1536328544.129701672]: Left Rectified image received from ZED - Size: 1280x720
[ INFO] [1536328544.131353933]: Right Rectified image received from ZED - Size: 1280x720
[...]
The code #
The source code of the subscriber node zed_video_sub_tutorial.cpp
:
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
/**
* Subscriber callbacks. The argument of the callback is a constant pointer to the received message
*/
void imageRightRectifiedCallback(const sensor_msgs::Image::ConstPtr& msg) {
ROS_INFO("Right Rectified image received from ZED - Size: %dx%d",
msg->width, msg->height);
}
void imageLeftRectifiedCallback(const sensor_msgs::Image::ConstPtr& msg) {
ROS_INFO("Left Rectified image received from ZED - Size: %dx%d",
msg->width, msg->height);
}
/**
* Node main function
*/
int main(int argc, char** argv) {
// Node initialization
ros::init(argc, argv, "zed_video_subscriber");
ros::NodeHandle n;
// Subscribers
ros::Subscriber subRightRectified = n.subscribe("/zed/zed_node/right/image_rect_color", 10,
imageRightRectifiedCallback);
ros::Subscriber subLeftRectified = n.subscribe("/zed/zed_node/left/image_rect_color", 10,
imageLeftRectifiedCallback);
// Node execution
ros::spin();
return 0;
}
The code explained #
The following is a brief explanation of the source code above:
void imageRightRectifiedCallback(const sensor_msgs::Image::ConstPtr& msg) {
ROS_INFO("Right Rectified image received from ZED - Size: %dx%d", msg->width, msg->height);
}
void imageLeftRectifiedCallback(const sensor_msgs::Image::ConstPtr& msg) {
ROS_INFO("Left Rectified image received from ZED - Size: %dx%d", msg->width, msg->height);
}
These callbacks are executed when the subscriber node receives a message of type sensor_msgs/Image
that matches the subscribed topic.
The parameter of the callback is a boost::shared_ptr
to the received message. This means you don’t have to worry
about memory management.
The callback code is very simple and demonstrates how to access the fields in a message;
in this case, the height
and width
of the image.
The main
function is very standard and is explained in detail in the “Talker/Listener” ROS tutorial.
The most important lesson of the above code is how the subscribers are defined:
// Subscribers
ros::Subscriber subRightRectified = n.subscribe("/zed/right/image_rect_color", 10, imageRightRectifiedCallback);
ros::Subscriber subLeftRectified = n.subscribe("/zed/left/image_rect_color", 10, imageLeftRectifiedCallback);
A ros::Subscriber
is a ROS object that listens on the network and waits for its own topic message to be available.
When a message is received, it executes the callback assigned to it.
We declared two subscribers: one for the left rectified image and one for the right rectified image.
- The subscriber to the
/zed/zed_node/right/image_rect_color
topic calls theimageRightRectCallback
function when it receives a message of typesensor_msgs/Image
that matches that topic - The subscriber to the
/zed/zed_node/left/image_rect_color
topic calls theimageLeftRectCallback
function when it receives a message of typesensor_msgs/Image
that matches that topic
Conclusion #
The full source code of this tutorial is available on GitHub in the zed_video_sub_tutorial sub-package.
Along with the node source code are the package.xml
and CMakeLists.txt
files that complete the tutorial package.