introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
999 stars 558 forks source link

Where depth scale is applied to a depth image and how that can be easily set for different depth image sources from different cameras #799

Open robotdream opened 2 years ago

robotdream commented 2 years ago

Hi,

I am starting to try rtabmap_ros and plan to make some development based on that. After some tests, The results looked fine for images from realsense sdk2 or realsense2_ros node, but I didn't evaluate that quantitively.

I am confused about where the right depth scale is multiplied with a depth image to get the right depth values for each pixel. After some initial search, I found the snip of code below in rgbd_sync.cpp that seems to do this job. But the output mat here with the type of CV_16U, not the float type that I think it should be. Based on my understanding, the original depth map should be converted to a float mat first and then scaled with a scale factor to get the actual depth values. Also, I am not sure where a depth scale is applied when the rgbd_sync node is not used. Is there any convenient configuration to deal with depth images from different cameras?

Any suggestions and help will be appreciated.

        cv::Mat rgbMat;
        cv::Mat depthMat;
        cv_bridge::CvImageConstPtr imagePtr = cv_bridge::toCvShare(image);
        cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(depth);
        rgbMat = imagePtr->image;
        depthMat = imageDepthPtr->image;

        if(decimation_>1)
        {
            rgbMat = rtabmap::util2d::decimate(rgbMat, decimation_);
            depthMat = rtabmap::util2d::decimate(depthMat, decimation_);
        }

        if(depthScale_ != 1.0)
        {
            depthMat*=depthScale_;
        }
robotdream commented 2 years ago

Noticed some code in getDepth from util2d.cpp. Looks like depth scale 0.001m is fixed for the format of 16UC1 regardless of the rgbd camera used.

matlabbe commented 2 years ago

I just verified with a simple code

cv::Mat m = cv::Mat::ones(3,3,CV_16U)*1000;
std::cout << m << m.type() << std::endl;
std::cout << m * 1.5f << m.type() << std::endl;

//output:
[1000, 1000, 1000;
 1000, 1000, 1000;
 1000, 1000, 1000]2
[1500, 1500, 1500;
 1500, 1500, 1500;
 1500, 1500, 1500]2

, and this https://github.com/introlab/rtabmap_ros/blob/cb28a86492370ae941e3dd047747f7dd7cd6cb97/src/nodelets/rgbd_sync.cpp#L237-L240 should work with CV_16U matrix format too.

The depth scale 0.001m is fixed before it is a conversion between mm and meters. CV_16U format is assumed to be in mm, and CV_32F is assumed to be in m.

For the depth_scale parameter of rgbd_sync node, this should never be used normally. I added it to support rosbags from TUM RGBD dataset for which depth images should be scaled by a factor of 4. If you are using your own cameras, the depth images should not need to be re-scaled.. If there is a scale issue with your camera, this is a bug on their driver side or the camera should be re-calibrated.