Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

question about align the color and depth image #9001

Closed
yuan0623 opened this issue May 12, 2021 · 5 comments
Closed

question about align the color and depth image #9001

yuan0623 opened this issue May 12, 2021 · 5 comments

Comments

@yuan0623
Copy link


Required Info
Camera Model D435
Firmware Version 05.12.12.100
Operating System & Version Ubuntu 18
Kernel Version (Linux Only) 5.4.0-72-generic
Platform PC
SDK Version 2.0
Language C++
Segment Robot

Issue Description

I have a question about the align the color and depth image.
What exactly is aligned here?

I use roslaunch realsense2_camera rs_camera.launch align_depth:=true, and I check the camera info from /camera/aligned_depth_to_color/camera_info and /camera/color/camera_info, I find that they have same K (intrinsic).
Then my understanding is: align means to make sure the color camera and depth camera have the same K (intrinsic)

However, in my cpp project, the camera intrinsic between the color camera and depth camera is still different after I aligned them. So what exactly are aligned here? Am I doing it wrong?
Here is my cpp code for aligning the color camera and the depth camera:

#include <iostream>
#include<opencv2/aruco.hpp>
#include<opencv2/opencv.hpp>
#include <librealsense2/rs.hpp>
#include <librealsense2/rsutil.h>
#include <numeric>
#include "example.hpp"
int main(int argc, char * argv[]) try
{


    rs2::log_to_console(RS2_LOG_SEVERITY_ERROR);


    // Declare depth colorizer for pretty visualization of depth data
    rs2::colorizer color_map;
    // Declare rates printer for showing streaming rates of the enabled streams.
    rs2::rates_printer printer;

    // get the device
    rs2::context ctx;
    auto list = ctx.query_devices();

    // Declare RealSense pipeline, encapsulating the actual device and sensors
    rs2::pipeline pipe;
    rs2::config cfg;
    cfg.enable_stream(RS2_STREAM_COLOR, 1280, 720, RS2_FORMAT_BGR8, 30);
    cfg.enable_stream(RS2_STREAM_DEPTH, 1280, 720, RS2_FORMAT_Z16, 30);

    rs2::points points;
    rs2::pointcloud pc;
    // Start streaming with default recommended configuration
    // The default video configuration contains Depth and Color streams
    // If a device is capable to stream IMU data, both Gyro and Accelerometer are enabled by default
    rs2::pipeline_profile pipeProfile = pipe.start(cfg);

    rs2::align align_to_depth(RS2_STREAM_DEPTH);
    rs2::align align_to_color(RS2_STREAM_COLOR);




    rs2::depth_sensor depth_sensor = pipeProfile.get_device().first < rs2::depth_sensor >();





    while (true) // Application still alive?
    {
        rs2::frameset frames = pipe.wait_for_frames();
        // align the depth camera to color camera
        frames = align_to_color.process(frames);
        rs2::video_frame video = frames.get_color_frame();
        rs2::depth_frame depth = frames.get_depth_frame();

        rs2_intrinsics depth_intrinsics = pipeProfile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>().get_intrinsics();
        rs2_intrinsics color_intrinsics = pipeProfile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>().get_intrinsics();
        const int w = video.get_width();
        const int h = video.get_height();

        
        std::cout<<"************depth***********"<<std::endl;
        std::cout<<depth_intrinsics.model<<std::endl;
        std::cout<<depth_intrinsics.ppx<<std::endl;
        std::cout<<depth_intrinsics.ppy<<std::endl;
        std::cout<<depth_intrinsics.fx<<std::endl;
        std::cout<<depth_intrinsics.fy<<std::endl;
        std::cout<<"************color***********"<<std::endl;
        std::cout<<color_intrinsics.model<<std::endl;
        std::cout<<color_intrinsics.ppx<<std::endl;
        std::cout<<color_intrinsics.ppy<<std::endl;
        std::cout<<color_intrinsics.fx<<std::endl;
        std::cout<<color_intrinsics.fy<<std::endl;
        }        
    }

    return EXIT_SUCCESS;
}
catch (const rs2::error & e)
{
    std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n    " << e.what() << std::endl;
    return EXIT_FAILURE;
}
catch (const std::exception& e)
{
    std::cerr << e.what() << std::endl;
    return EXIT_FAILURE;
}

However, from the output, we know that the intrinsic of the color camera and the depth camera is not the same.
Am I understanding it wrong?
align

Best
Yuan

@MartyG-RealSense
Copy link
Collaborator

Hi @yuan0623 If you are aligning in librealsense with the Align Processing Block (align_to) then the processing block resizes the field of view (FOV) size of the stream that is being aligned to the FOV size of the stream that is being aligned to.

So if depth to color alignment is being performed then the depth FOV is resized to the color FOV size. On the D435 / D435i models where the color FOV is smaller than the depth FOV, this can cause the outer regions of the depth image to be cut off.

The opening section of the documentation for the SDK's C++ rs-align example provides further information about the principles of alignment.

https://github.com/IntelRealSense/librealsense/tree/master/examples/align

@yuan0623
Copy link
Author

Hi @yuan0623 If you are aligning in librealsense with the Align Processing Block (align_to) then the processing block resizes the field of view (FOV) size of the stream that is being aligned to the FOV size of the stream that is being aligned to.

So if depth to color alignment is being performed then the depth FOV is resized to the color FOV size. On the D435 / D435i models where the color FOV is smaller than the depth FOV, this can cause the outer regions of the depth image to be cut off.

The opening section of the documentation for the SDK's C++ rs-align example provides further information about the principles of alignment.

https://github.com/IntelRealSense/librealsense/tree/master/examples/align

Hi Marty,

Thanks again for your patience explanation, Here is my understanding:

  1. In librealsense, align_to will only ensure the depth camera has the same size as the RGB camera, but the intrinsic of two cameras are still different.
  2. In ROS, with roslaunch realsense2_camera rs_camera.launch align_depth:=true, we can ensure not only the size of images but also the intrinsic of two cameras are the same.

@MartyG-RealSense
Copy link
Collaborator

MartyG-RealSense commented May 14, 2021

  1. My understanding is that depth and color would still have separate intrinsics, but when aligning you can use the intrinsics of the stream that you have aligned to (i.e if you are using depth to color alignment then use the color intrinsics).

#3735 (comment)

  1. What align_depth does in the ROS wrapper when set to True is to publish the additional aligned depth to color topics /camera/aligned_depth_to_color/image_raw and /camera/aligned_depth_to_color/camera_info

Whilst you can custom-define the size of the image resolution for each stream type in the roslaunch instruction or in the launch file (e.g 848x480 for both depth and color), as far as I know align_depth does not change the intrinsics of the individual streams.

@yuan0623
Copy link
Author

  1. My understanding is that depth and color would still have separate intrinsics, but when aligning you can use the intrinsics of the stream that you have aligned to (i.e if you are using depth to color alignment then use the color intrinsics).

#3735 (comment)

  1. What align_depth does in the ROS wrapper when set to True is to publish the additional aligned depth to color topics /camera/aligned_depth_to_color/image_raw and /camera/aligned_depth_to_color/camera_info

Whilst you can custom-define the size of the image resolution for each stream type in the roslaunch instruction or in the launch file (e.g 848x480 for both depth and color), as far as I know align_depth does not change the intrinsics of the individual streams.

MartyG

Thanks so much for your explanation!

Best
Yuan

@MartyG-RealSense
Copy link
Collaborator

You are very welcome @yuan0623 - thanks very much for the update!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

2 participants