D435i相机获取某一点深度图像的深度值(ROS实现以及官方API调用)

文章目录


前言


最近这段时间一直在研究intel的D435i相机,主要用来实现识别物体并反馈物体的深度值。特别强调一点,通常所说图片的深度信息、深度值指的就是深度图像中相机到物体的距离。
由于初次使用intel相机,并没有什么开发经验,因此多走了不少弯路,特意写下这篇博客,希望大家能够少走一下弯路。


一、ROS实现深度值的获取

由于我的整个项目是在Linux环境下开发的,基于ROS实现图像深度值得获取。一开始的想法是先通过学习官方API了解D435i相机的使用,然后将其转化为ROS语言,用来实现我的需求,但是通过了解官方链接的一些函数以及例子后,运行官方教程的程序,发现设备被占用的问题,主要原因是我运行了rs_camera.launch文件,然后启动自己写的调用官方API接口的程序,然后关闭了rs_camera.launch 文件后就不会出现设备被占用的问题了。但是没法实现将程序修改成ROS语言,好在最后通过查阅资料最终实现了ROS环境获取图像深度值。
在此附上参考的资料:
链接1
链接2
链接3
话不多说,下面附上自己写的ROS获取深度:

#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <iostream>
#include <opencv2/opencv.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include<realsense_dev/depth_value.h>       //自定义一个消息类型
 
using namespace std;

using namespace cv;
 
cv::Mat depth_pic;        //定义全局变量,图像矩阵Mat形式
float d_value;
realsense_dev::depth_value command_to_pub;   //待发布数据

void depthCallback(const sensor_msgs::Image::ConstPtr&msg)
{
    cv_bridge::CvImagePtr Dest ;
    Dest = cv_bridge::toCvCopy(msg,sensor_msgs::image_encodings::TYPE_16UC1);

    depth_pic = Dest->image;
    //cout<<"Output some info about the depth image in cv format"<<endl;
    //cout<< "Rows of the depth iamge = "<<depth_pic.rows<<endl;                       //获取深度图的行数height
    //cout<< "Cols of the depth iamge = "<<depth_pic.cols<<endl;                           //获取深度图的列数width
    //cout<< "Type of depth_pic's element = "<<depth_pic.type()<<endl;             //深度图的类型
    ushort d = depth_pic.at<ushort>(depth_pic.rows/2,depth_pic.cols/2);           //读取深度值,数据类型为ushort单位为mm
    d_value = float(d)/1000 ;      //强制转换
    cout<< "Value of depth_pic's pixel= "<<d_value<<endl;    //读取深度值

}



int main(int argc, char **argv)
{
    ros::init(argc, argv, "stream_pub");               // ros节点初始化
    ros::NodeHandle nh;                                           //创建节点句柄
    ros::AsyncSpinner spinner(1);
    spinner.start();

    ros::Subscriber image_sub = nh.subscribe<sensor_msgs::Image>("/camera/aligned_depth_to_color/image_raw",1,depthCallback);   //订阅深度图像
    //ros::Subscriber element_sub = nh.subscribe<sensor_msgs::Image>("/camera/aligned_depth_to_color/image_raw",100,pixelCallback);     //订阅像素点坐标
    ros::Publisher mode_pub = nh.advertise<realsense_dev::depth_value>("/depth_info", 10);

    command_to_pub.Value = 0;    //初始化深度值
    ros::Rate rate(20.0);    //设定自循环的频率
    while(ros::ok)
    {
        command_to_pub.header.stamp      = ros::Time::now();
        command_to_pub.Value = d_value;     //depth_pic.rows/2,depth_pic.cols/2  为像素点
        mode_pub.publish(command_to_pub);
    }
    
    ros::Duration(10).sleep();    //设定自循环的频率
    return 0 ;
}

代码解释

在这里我自定义了一个msg消息,主要是ROS发布某一像素点的深度值,在本示例中是获取图像中心点的深度值,然后通过ROS发布话题。

void depthCallback(const sensor_msgs::Image::ConstPtr&msg)
{
    cv_bridge::CvImagePtr Dest ;
    Dest = cv_bridge::toCvCopy(msg,sensor_msgs::image_encodings::TYPE_16UC1);

    depth_pic = Dest->image;
    //cout<<"Output some info about the depth image in cv format"<<endl;
    //cout<< "Rows of the depth iamge = "<<depth_pic.rows<<endl;                       //获取深度图的行数height
    //cout<< "Cols of the depth iamge = "<<depth_pic.cols<<endl;                           //获取深度图的列数width
    //cout<< "Type of depth_pic's element = "<<depth_pic.type()<<endl;             //深度图的类型
    ushort d = depth_pic.at<ushort>(depth_pic.rows/2,depth_pic.cols/2);           //读取深度值,数据类型为ushort单位为mm
    d_value = float(d)/1000 ;      //强制转换
    cout<< "Value of depth_pic's pixel= "<<d_value<<endl;    //读取深度值

}

这部分是通过订阅相机发布的/camera/aligned_depth_to_color/image_raw话题的回调函数,在回调函数中将原始深度图像通过cv_bridge转换格式,然后通过at方式获取某一像素点的深度值,这里的深度值就代表的是图像中该点与相机的距离。
本人纯属视觉处理小白,因此在处理cv_bridge转换后的图片数据花了很多功夫,上面附加的3个链接可以很好的帮助我们理解。另外在这里附上ROS官网给出的图像消息类型:http://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html

二.使用方法

在使用前,开启rs_camera.launch 文件,其中需要修改参数配置,将深度图对齐到颜色图上,然后运行程序节点。注意修改cmakelist文件以及package.xml文件,下面是我的cmakelist文件

cmake_minimum_required(VERSION 3.0.2)
project(realsense_dev)

## Compile as C++11, supported in ROS Kinetic and newer
#add_compile_options(-std=c++11)
set(CMAKE_CXX_STANDARD 11)
set(CMAKE_CXX_STANDARD_REQUIRED True)

find_library(librealsense REQUIRED)

find_package(catkin REQUIRED COMPONENTS
  geometry_msgs
  roscpp
  rospy
  std_msgs
  cv_bridge
  message_generation
  image_transport
)
find_package(realsense2 REQUIRED)
find_package(OpenCV REQUIRED)


    add_message_files(FILES depth_value.msg)
    generate_messages(DEPENDENCIES std_msgs)


catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES realsense_dev
   CATKIN_DEPENDS geometry_msgs roscpp rospy std_msgs  message_runtime
#  DEPENDS system_lib
)


include_directories(
# include
  ${catkin_INCLUDE_DIRS}
  ${OpenCV_INCLUDE_DIRS}
)

add_executable(stream_pub src/stream_pub.cpp)
target_link_libraries(stream_pub ${catkin_LIBRARIES} ${OpenCV_LIBS})

三.调用官方API获取深度

注意,在调用官方API的时候不能开启相机其他节点,不然会出现设备占用问题,这也就是上面提到的为什么一开始的想法被pass掉了。但是在这里还是附上我的代码,走了一大圈弯路,在这里也可以让初入D435i相机的小伙伴少走一些坑。

#include <iostream>
 
using namespace std;
#include <sstream>
#include <iostream>
#include <fstream>
#include <algorithm>
#include<string>
 
#include<opencv2/imgproc/imgproc.hpp>
#include<opencv2/core/core.hpp>
#include<opencv2/highgui/highgui.hpp>
using namespace cv;
 
#include<librealsense2/rs.hpp>
#include<librealsense2/rsutil.h>

//获取深度像素对应长度单位(米)的换算比例
float get_depth_scale(rs2::device dev)
{
    // Go over the device's sensors  检查设备的传感器
    for (rs2::sensor& sensor : dev.query_sensors())
    {
        // Check if the sensor if a depth sensor  检查设备是否是一个深度传感器
        if (rs2::depth_sensor dpt = sensor.as<rs2::depth_sensor>())
        {
            return dpt.get_depth_scale();           //函数的作用是检索深度图像和米之间的映射,返回的是深度,单位是米
        }
    }
    throw std::runtime_error("Device does not have a depth sensor");                   //throw是抛出异常
}

//深度图对齐到彩色图函数
Mat align_Depth2Color(Mat depth,Mat color,rs2::pipeline_profile profile){
    
    //声明数据流
    auto depth_stream=profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();                  //profile 是声明的数据流   RS2_STREAM_DEPTH是深度数据流
    auto color_stream=profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();               //RS2_STREAM_COLOR颜色数据流
 
    //获取内参
    const auto intrinDepth=depth_stream.get_intrinsics();
    const auto intrinColor=color_stream.get_intrinsics();
 
    //直接获取从深度摄像头坐标系到彩色摄像头坐标系的欧式变换矩阵
    //auto  extrinDepth2Color=depth_stream.get_extrinsics_to(color_stream);
    rs2_extrinsics  extrinDepth2Color;
    rs2_error *error;
    rs2_get_extrinsics(depth_stream,color_stream,&extrinDepth2Color,&error);
 
    //平面点定义
    float pd_uv[2],pc_uv[2];
    //空间点定义
    float Pdc3[3],Pcc3[3];
 
    //获取深度像素与现实单位比例(D435默认1毫米)
    float depth_scale = get_depth_scale(profile.get_device());
    int y=0,x=0;
    //初始化结果
    //Mat result=Mat(color.rows,color.cols,CV_8UC3,Scalar(0,0,0));
    Mat result=Mat(color.rows,color.cols,CV_16U,Scalar(0));
    //对深度图像遍历
    for(int row=0;row<depth.rows;row++){
        for(int col=0;col<depth.cols;col++){
            //将当前的(x,y)放入数组pd_uv,表示当前深度图的点
            pd_uv[0]=col;
            pd_uv[1]=row;
            //取当前点对应的深度值
            uint16_t depth_value=depth.at<uint16_t>(row,col);
            //换算到米
            float depth_m=depth_value*depth_scale;
            //将深度图的像素点根据内参转换到深度摄像头坐标系下的三维点
            rs2_deproject_pixel_to_point(Pdc3,&intrinDepth,pd_uv,depth_m);
            //将深度摄像头坐标系的三维点转化到彩色摄像头坐标系下
            rs2_transform_point_to_point(Pcc3,&extrinDepth2Color,Pdc3);
            //将彩色摄像头坐标系下的深度三维点映射到二维平面上
            rs2_project_point_to_pixel(pc_uv,&intrinColor,Pcc3);
 
            //取得映射后的(u,v)
            x=(int)pc_uv[0];
            y=(int)pc_uv[1];
//            if(x<0||x>color.cols)
//                continue;
//            if(y<0||y>color.rows)
//                continue;
            //最值限定
            x=x<0? 0:x;
            x=x>depth.cols-1 ? depth.cols-1:x;
            y=y<0? 0:y;
            y=y>depth.rows-1 ? depth.rows-1:y;
 
            result.at<uint16_t>(y,x)=depth_value;
        }
    }
    //返回一个与彩色图对齐了的深度信息图像
    return result;
}
 
void measure_distance(Mat &color,Mat depth,cv::Size range,rs2::pipeline_profile profile)
{
    //获取深度像素与现实单位比例(D435默认1毫米)
    float depth_scale = get_depth_scale(profile.get_device());
    //定义图像中心点
    cv::Point center(color.cols/2,color.rows/2);
    //定义计算距离的范围
    cv::Rect RectRange(center.x-range.width/2,center.y-range.height/2,range.width,range.height);
    //遍历该范围
    float distance_sum=0;
    int effective_pixel=0;
    for(int y=RectRange.y;y<RectRange.y+RectRange.height;y++){
        for(int x=RectRange.x;x<RectRange.x+RectRange.width;x++){
            //如果深度图下该点像素不为0,表示有距离信息
            if(depth.at<uint16_t>(y,x)){
                distance_sum+=depth_scale*depth.at<uint16_t>(y,x);
                effective_pixel++;
            }
        }
    }
    cout<<"遍历完成,有效像素点:"<<effective_pixel<<endl;
    float effective_distance=distance_sum/effective_pixel;
    cout<<"目标距离:"<<effective_distance<<" m"<<endl;
    char distance_str[30];
    sprintf(distance_str,"the distance is:%f m",effective_distance);
    cv::rectangle(color,RectRange,Scalar(0,0,255),2,8);
    cv::putText(color,(string)distance_str,cv::Point(color.cols*0.02,color.rows*0.05),
                cv::FONT_HERSHEY_PLAIN,2,Scalar(0,255,0),2,8);
}
 
int main()
{
    const char* depth_win="depth_Image";
    namedWindow(depth_win,WINDOW_AUTOSIZE);
    const char* color_win="color_Image";
    namedWindow(color_win,WINDOW_AUTOSIZE);
 
    //深度图像颜色map
    rs2::colorizer c;                          // Helper to colorize depth images
 
    //创建数据管道
    rs2::pipeline pipe;
    rs2::config pipe_config;
    pipe_config.enable_stream(RS2_STREAM_DEPTH,640,480,RS2_FORMAT_Z16,30);
    pipe_config.enable_stream(RS2_STREAM_COLOR,640,480,RS2_FORMAT_BGR8,30);
 
    //start()函数返回数据管道的profile
    rs2::pipeline_profile profile = pipe.start(pipe_config);
 
    //定义一个变量去转换深度到距离
    float depth_clipping_distance = 1.f;
 
    //声明数据流
    auto depth_stream=profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
    auto color_stream=profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
 
    //获取内参
    auto intrinDepth=depth_stream.get_intrinsics();
    auto intrinColor=color_stream.get_intrinsics();
 
    //直接获取从深度摄像头坐标系到彩色摄像头坐标系的欧式变换矩阵
    auto  extrinDepth2Color=depth_stream.get_extrinsics_to(color_stream);
 
    while (cvGetWindowHandle(depth_win)&&cvGetWindowHandle(color_win)) // Application still alive?
    {
        //堵塞程序直到新的一帧捕获
        rs2::frameset frameset = pipe.wait_for_frames();
        //取深度图和彩色图
        rs2::frame color_frame = frameset.get_color_frame();//processed.first(align_to);
        rs2::frame depth_frame = frameset.get_depth_frame();
        rs2::frame depth_frame_4_show = frameset.get_depth_frame().apply_filter(c);
        //获取宽高
        const int depth_w=depth_frame.as<rs2::video_frame>().get_width();
        const int depth_h=depth_frame.as<rs2::video_frame>().get_height();
        const int color_w=color_frame.as<rs2::video_frame>().get_width();
        const int color_h=color_frame.as<rs2::video_frame>().get_height();
 
        //创建OPENCV类型 并传入数据
        Mat depth_image(Size(depth_w,depth_h),
                                CV_16U,(void*)depth_frame.get_data(),Mat::AUTO_STEP);
        Mat depth_image_4_show(Size(depth_w,depth_h),
                                CV_8UC3,(void*)depth_frame_4_show.get_data(),Mat::AUTO_STEP);
        Mat color_image(Size(color_w,color_h),
                                CV_8UC3,(void*)color_frame.get_data(),Mat::AUTO_STEP);
        //实现深度图对齐到彩色图
        Mat result=align_Depth2Color(depth_image,color_image,profile);
        measure_distance(color_image,result,cv::Size(20,20),profile);
        //显示
        imshow(depth_win,depth_image_4_show);
        imshow(color_win,color_image);
        //imshow("result",result);
        waitKey(1);
    }
    return 0;
}

代码不再过多介绍,想要了解更多信息的小伙伴可以自行百度,这里附上相关链接:

1、官方例程:https://dev.intelrealsense.com/docs/rs-hello-realsense
2、深度图与颜色对齐1
3、深度图与颜色对齐2
4、从二维图像获取三维空间坐标


总结

从拿到D435i相机到现在的开发,目前只是刚刚入门一小部分,后面将继续深入了解,研究深度相机实现定位问题,有做视觉避障、视觉定位方向的小伙伴可以私信或留言,大家一起学习交流。
以上内容纯属本人对D435i相机的初入了解,有错误的地方还请大家批评指正,感谢阅读。

上一篇:2.4 FrozenLake使用cross-entropy方法


下一篇:AXI4-Stream/AXI4-lite,SPI,I2C,AMBA标准接口