Realsense2 Camera
机器人上装备了intel RealSense D435摄像头,可以获得RGB和深度图像,realsense_ros 包是intel提供的用于调用D435摄像头的ros功能包。
启动摄像头
realsense_ros 包位置
/home/lemon/robot_ros_application/catkin_ws/src/realsense/realsense2_camera
launch文件路径
/home/lemon/robot_ros_application/catkin_ws/src/realsense/realsense2_camera/launch/RobanD435camera.launch
使用launch文件启动摄像头
source ~/robot_ros_application/catkin_ws/devel/setup.bash
roslaunch realsense2_camera RobanD435camera.launch
节点输出topic
节点发布的主题主要有:
相机内参
/camera/color/camera_info
rgb图像信息
/camera/color/image_raw
未对齐的深度信息
/camera/depth/image_rect_raw
与rgb图像对齐的深度信息
/camera/aligned_depth_to_color/image_raw
需要在launch文件中设置align_depth参数为true才有这个主题输出
订阅RGB图像
Python 示例
#! /usr/bin/env python
# coding=UTF-8
import rospy # ros 的 python 库
from cv_bridge import CvBridge, CvBridgeError # 用于将 msg 数据类型的图像转成 opencv 图像格式的库
from sensor_msgs.msg import Image # topic 的消息类型
import cv2 # opencv-python 库
import numpy as np
class Vision():
def __init__(self):
self.topic_name = '/camera/color/image_raw' # 消息名称
self.__cv_bridge = CvBridge()
rospy.Subscriber(self.topic_name, Image, self.__image_callback, queue_size=1) # 定义消息订阅者,包含消息名称、消息类型、消息回调及队列大小等
def __image_callback(self, msg): # 消息回调函数,收到的消息在 msg 中
try:
image_origin = self.__cv_bridge.imgmsg_to_cv2(msg, msg.encoding) # 通过cv_bridge转化为numpy矩阵格式
except CvBridgeError as err:
rospy.logerr(err)
return
print("image shape is {}".format(image_origin.shape)) # 打印图片的shape
cv2.imshow("image",image_origin) # 显示图片
cv2.waitKey(1)
def rosShutdownHook(): # 当节点退出时会调用
rospy.loginfo("VisionTest node is killed.")
if __name__ == "__main__":
rospy.init_node("VisionTest", anonymous=True) # 初始化 ros 节点
rospy.on_shutdown(rosShutdownHook) # 设置节点退出时的调用
chinV = Vision()
rospy.spin()以上示例通过订阅'/camera/color/image_raw'主题获取到rgb图像消息,通过cv_bridge将ros消息转换为opencv图片格式(即numpy数组)并显示。
订阅深度信息
Python 示例
#! /usr/bin/env python
# coding=UTF-8
import rospy # ros 的 python 库
from cv_bridge import CvBridge, CvBridgeError # 用于将 msg 数据类型的图像转成 opencv 图像格式的库
from sensor_msgs.msg import Image # topic 的消息类型
import cv2 # opencv-python 库
import numpy as np
class Vision():
def __init__(self):
self.topic_name = '/camera/aligned_depth_to_color/image_raw' # 消息名称
self.__cv_bridge = CvBridge()
rospy.Subscriber(self.topic_name, Image, self.__image_callback, queue_size=1) # 定义消息订阅者,包含消息名称、消息类型、消息回调及队列大小等
def __image_callback(self, msg): # 消息回调函数,收到的消息在 msg 中
try:
image_origin = self.__cv_bridge.imgmsg_to_cv2(msg, msg.encoding) # 通过cv_bridge转化为numpy矩阵格式
except CvBridgeError as err:
rospy.logerr(err)
return
print("depth shape is {}".format(image_origin.shape))
def rosShutdownHook(): # 当节点退出时会调用
rospy.loginfo("VisionTest node is killed.")
if __name__ == "__main__":
rospy.init_node("VisionTest", anonymous=True) # 初始化 ros 节点
rospy.on_shutdown(rosShutdownHook) # 设置节点退出时的调用
chinV = Vision()
rospy.spin()通过以上示例,可以从
/camera/aligned_depth_to_color/image_raw
主题获取到与rgb图片对齐的深度图像矩阵,大小为 (高x宽)=(480x640)。获取到该矩阵后,即可单独提取出图像中每个像素点的距离,单位为mm(注意如某些区域获取到的距离为0表示像素点的距离无效,最小深度距离约为 0.28m)