Using the RealSense SDK to access the camera

The RealSense SDK provides an API for accessing the camera hardware directly. Accessing the camera via the SDK locks it, until access is released. This tutorial will cover how to use the RealSense SDK for C++ development using the simple example of accessing the camera’s intrinsic calibration parameters.

Recall that the intrinsic camera matrix for raw (distorted) images is given by a 3×3 matrix:

K = [fx 0 cx; 
     0 fy cy; 
     0  0  1]

where (cx, cy) is the principal point and (fx, fy)  is the pixel focal length. This matrix projects 3D points in the camera coordinate frame to 2D pixel.

RealSense SDK setup

Librealsense is the RealSense library that is installed by the SDK 2.0 (as described in Integrating the Intel Realsense D435 with ROS). Detailed Doxygen generated API documentation can be found here alongside the librealsense Wiki which contains a number of useful tutorials. Once this library is installed, new applications can be compiled with librealsense using g++ -std=c++11 filename.cpp -lrealsense2.
Adding librealsense2 to your C++ application requires three simple steps:

    1. Include the librealsense2 header in your C++ file: #include <librealsense2/rs.hpp>. The rs.hpp header file actually points to other header files for the camera such as rs_device.hpp, rs_frame.hpp, rs_processing.hpp, and rs_pipeline.hpp.
    2. Update your CMakeLists.txt file to point to the librealsense library by adding the following lines to the file: target_link_libraries(YourExcecutableName ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS} -lrealsense2). In this example, the target is linked to the catkin, PCL, OpenCV, and RealSense libraries as this is a ROS based project.
    3. Update your compiler flags to use C++11 which is required by librealsense. This support can be enabled with the -std=c++11 or -std=gnu++11 compiler options. To do this, add this line to the top your CMakeLists.txt file: add_compile_options(-std=c++11).

Using the C++ SDK to access camera parameters

Let us now consider the simple example of extracting the camera’s video stream intrinsic parameters. The code snippet used below expands upon the example found in the RealSense API How To guide.

#include <librealsense2/rs.hpp>
#include 
using namespace std;

int main()
{
    //get camera parameters
    rs2::pipeline pipe;
    rs2::pipeline_profile selection = pipe.start();
    auto depth_stream = selection.get_stream(RS2_STREAM_COLOR).as();
    auto resolution = std::make_pair(depth_stream.width(), depth_stream.height());
    auto i = depth_stream.get_intrinsics();
    auto principal_point = std::make_pair(i.ppx, i.ppy);
    auto focal_length = std::make_pair(i.fx, i.fy);
    rs2_distortion model = i.model;
    //print the parameters
    cout << "Resolution: " << resolution.first << "," << resolution.second << endl;
    cout << "Principle point: " << principal_point.first << "," << principal_point.second << endl;
    cout << "Focal length: " << focal_length.first << "," << focal_length.second << endl;
    return 0;
}

The output of the above program is shown below:

ProgramCalib

The resolution is required because the principal point (cx, cy) and pixel focal lengths (fx, fy) values should be scaled appropriately. If a camera has been calibrated on images of 320×240 resolution, the cx, cy, fx, fy values should be scaled appropriately for 640×480 images from the same camera.

The line selection.get_stream(RS2_STREAM_COLOR).as() contains an rs2_stream enum which specifies which camera stream to select (RGB, infrared, depth etc.). Here, RS2_STREAM_COLOR is the native RGB colour stream, and similarly, RS2_STREAM_DEPTH is the native depth data produced by the RealSense camera. A full list of the enum options can be found under rs2_stream here.

Accessing the camera parameters in ROS

The RealSense ROS nodelet (covered previously in Integrating the Intel RealSense D435 with ROS) conveniently publishes the camera’s intrinsic calibration parameters on the /camera/color/camera_info  ROS topic which publishes messages of type sensor_msgs/CameraInfo.

These messages can be directly accessed by subscribing to this topic inside a ROS node, or simply inspecting it using rostopic echo /camera/color/camera_info, the output of which is shown below.

TerminalCalib

Inspecting the camera intrinsic parameters via ROS topic echo

The parameter K contains the intrinsic camera parameters, and the resolution is given by width, height.

Troubleshooting

A common mistake is to try to access the camera whilst it is still being used by another process (such as the realsense-viewer application, ROS, or a standalone application built with the SDK). When this happens, the error message shown is usually something like:
terminate called after throwing an instance of ‘rs2::backend_error’
what():  xioctl(VIDIOC_S_FMT) failed Last Error: Device or resource busy

To fix this, simply shutdown any process that his using the camera before attempting to connect to it again.

Leave a Reply

Fill in your details below or click an icon to log in:

WordPress.com Logo

You are commenting using your WordPress.com account. Log Out /  Change )

Twitter picture

You are commenting using your Twitter account. Log Out /  Change )

Facebook photo

You are commenting using your Facebook account. Log Out /  Change )

Connecting to %s