正好实验室有Intel的D435i 深度相机,拿过来玩一玩。
一、安装驱动
这一步分两个环节,一是安装librealsense SDK 2.0,使得ubuntu可以驱动D435,二是安装realsense-ros使得ROS可以获得相机的话题。
安装librealsense SDK 2.0参照了文章一,安装realsense-ros参照了文章二,完成驱动的安装后,终端输入rqt_image_view就可以看到相机发布的图像话题了,其中/camera/color/image_raw是彩色图像,/camera/depth/image_rect_raw是没有与彩色图对齐的深度图像(图片大小848*480),而 /camera/aligned_depth_to_color/image_raw则是与彩色图对齐的深度图像(需要将rs_camera.launch文件里的参数alien_depth的值改成true才能看到,大小640*480)。
roslaunch realsense2_camera rs_camera.launch align_depth:=true
可以看到深度图噪点数比较多,如果想得到比较干净的深度图,可以把rs_camera.launch文件里的参数filters的值修改掉。
如果要打开双目相机的深度图,需要enable_infra。
二、编写代码获取深度值
D435得到的深度图是十六位整数类型的(uint16),单位mm,如果要用opencv的imshow显示,需要进行一定的处理才能得到效果比较好的深度图,先放上自己调用D435获得彩色图和深度图的代码,参考了这篇文章。
#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 <stdlib.h>
#include <opencv2/opencv.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
int rowNumber = 480;
int colNumber = 640;
float d_value;
cv::Mat depth_pic; //定义全局变量,图像矩阵Mat形式
cv::Mat rgb_image = cv::Mat::zeros(rowNumber, colNumber, CV_8UC3);
cv::Mat depth = cv::Mat::zeros(rowNumber, colNumber, CV_8UC1); //定义全局变量,图像矩阵Mat形式
void depthCallback(const sensor_msgs::Image::ConstPtr&msg)
{
for (int i = 0; i < rowNumber; i++) {
for (int j = 0; j < colNumber; j++) {
d_value = 25.5*depth_pic.at<ushort>(i,j)/1000.0;
depth.at<unsigned char>(i,j) = d_value;
}
}
cv::imshow("Depth", depth);
cv::waitKey(10);
}
void ColorCallback(const sensor_msgs::Image::ConstPtr&msg)
{
rgb_image = cv_bridge::toCvCopy(*msg, sensor_msgs::image_encodings::TYPE_8UC3)->image;//输入为图像消息指针和编码参数
cv::cvtColor(rgb_image,rgb_image, cv::COLOR_BGR2RGB);
cv::imshow("rgb_image", rgb_image);
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "d435"); // ros节点初始化
ros::NodeHandle n; //创建节点句柄
ros::Subscriber depth_sub = n.subscribe<sensor_msgs::Image>("/camera/aligned_depth_to_color/image_raw",5,&depthCallback); //订阅深度图像
ros::Subscriber color_sub = n.subscribe<sensor_msgs::Image>("/camera/color/image_raw",5,&ColorCallback); //订阅RGB图像
ros::spin();
return 0;
}
其中,我的catkin_ws工作空间创建的有点问题,于是参照这篇文章重新创建了下,其中,我将source ~/catkin_ws/devel/setup.bash直接写进了/.bashrc,并且source /.bashrc使其立即生效。
最后,先通过ROS打开相机
roslaunch realsense2_camera rs_camera.launch
再运行节点,就可以看到图像啦。
rosrun d435 uav_node