ROS通过话题发布订阅Image类型的视频帧(python)

ROS通过话题发布订阅Image类型的视频帧(python)

前言:

本文中,主要是关于OpenCV格式图片(或视频帧)和ROS数据格式图片(或视频帧)之间的转换。或者直白点书,通过ROS发送图片(Image)数据类型的消息(message)

本文其实是为下一篇博文“YOLOROS下的使用”打下基础。

1、使用环境和平台

ubuntu 18.04+ python2.7+opencv3

注意:使用python3的话提示报错,还是用python2
2、示例代码

其实,下述代码完全可以在一个脚本中完成,而且不需要结合ROS;本文为了讲述通过ROS发送Image的方法,故而拆分开来。一个脚本中,只进行图像捕捉;另一个订阅之后,只进行图像现实。

(1)通过调用webcam捕捉视频,然后经过ROSTopic发布出去:

#!/usr/bin/env python
#!coding=utf-8
 
#write by leo at 2018.04.26
#function: 
#1, Get live_video from the webcam.
#2, With ROS publish Image_info (to yolo and so on).
#3, Convert directly, don't need to save pic at local.
 
import rospy
from sensor_msgs.msg import Image
import cv2
import numpy as np
from cv_bridge import CvBridge, CvBridgeError
import sys
 
 
def webcamImagePub():
    # init ros_node
    rospy.init_node('webcam_puber', anonymous=True)
    # queue_size should be small in order to make it 'real_time'
    # or the node will pub the past_frame
    img_pub = rospy.Publisher('webcam/image_raw', Image, queue_size=2)
    rate = rospy.Rate(5) # 5hz
 
    # make a video_object and init the video object
    cap = cv2.VideoCapture(0)
    # define picture to_down' coefficient of ratio
    scaling_factor = 0.5
    # the 'CVBridge' is a python_class, must have a instance.
    # That means "cv2_to_imgmsg() must be called with CvBridge instance"
    bridge = CvBridge()
 
    if not cap.isOpened():
        sys.stdout.write("Webcam is not available !")
        return -1
 
    count = 0
    # loop until press 'esc' or 'q'
    while not rospy.is_shutdown():
        ret, frame = cap.read()
        # resize the frame
        if ret:
            count = count + 1
        else:
            rospy.loginfo("Capturing image failed.")
        if count == 2:
            count = 0
            frame = cv2.resize(frame,None,fx=scaling_factor,fy=scaling_factor,interpolation=cv2.INTER_AREA)
            msg = bridge.cv2_to_imgmsg(frame, encoding="bgr8")
            img_pub.publish(msg)
            print '** publishing webcam_frame ***'	
        rate.sleep()
 
if __name__ == '__main__':
    try:
        webcamImagePub()
    except rospy.ROSInterruptException:
        pass

(2)通过ROS订阅Image类型的视频帧,然后在窗口显示出来:

#!/usr/bin/env python
#!coding=utf-8
 
#right code !
#write by leo at 2018.04.26
#function: 
#display the frame from another node.
 
import rospy
import numpy as np
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import cv2
 
def callback(data):
    # define picture to_down' coefficient of ratio
    scaling_factor = 0.5
    global count,bridge
    count = count + 1
    if count == 1:
        count = 0
        cv_img = bridge.imgmsg_to_cv2(data, "bgr8")
        cv2.imshow("frame" , cv_img)
        cv2.waitKey(3)
    else:
        pass
 
def displayWebcam():
    rospy.init_node('webcam_display', anonymous=True)
 
    # make a video_object and init the video object
    global count,bridge
    count = 0
    bridge = CvBridge()
    rospy.Subscriber('webcam/image_raw', Image, callback)
    rospy.spin()
 
if __name__ == '__main__':
    displayWebcam()
 

当然,上面话题发布之后,也可以使用RVIZ工具箱的image工具进行显示

3、代码解释(函数讲解)

从代码中可以看出:

from cv_bridge import CvBridge, CvBridgeError

导入了一个模块下的两个类,然后实例化一个对象:

bridge = CvBridge()

接下来,调用该对象下的方法(函数):

msg = bridge.cv2_to_imgmsg(frame, encoding="bgr8")
img_pub.publish(msg)

发布信息的脚本(上程序(1)中)里,利用此方法将OpenCV类型的图片转化为ROS类型,然后通过话题发布出去;

然后:

cv_img = bridge.imgmsg_to_cv2(data, "bgr8")

订阅话题的脚本(上程序(2)中)里,利用此方法将订阅到的ROS类型的数据转化为OpenCV格式的图片,然后通过imshow函数在窗口显示出图像。

PS:上边的程序中,不论发布还是订阅,都可以跳过一些帧(通过改变count的值即可)。

4、参考链接

ROS初学者教程:

http://wiki.ros.org/cn/ROS/Tutorials

OpnCV-Python教程:

https://docs.opencv.org/3.0-beta/doc/py_tutorials/py_tutorials.html

Converting between ROS images and OpenCV images (Python)
https://answers.ros.org/question/226819/trouble-converting-cv2-to-imgmsg/
http://wiki.ros.org/cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython

https://github.com/pirobot/ros-by-example/blob/master/rbx_vol_1/rbx1_vision/nodes/cv_bridge_demo.py

版权声明:本文内容由互联网用户自发贡献,该文观点仅代表作者本人。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如发现本站有涉嫌侵权/违法违规的内容, 请发送邮件至 举报,一经查实,本站将立刻删除。

发布者:全栈程序员-用户IM,转载请注明出处:https://javaforall.cn/2145.html原文链接:https://javaforall.cn

【正版授权,激活自己账号】: Jetbrains全家桶Ide使用,1年售后保障,每天仅需1毛

【官方授权 正版激活】: 官方授权 正版激活 支持Jetbrains家族下所有IDE 使用个人JB账号...

(0)


相关推荐

  • Hive 数据类型

    Hive 数据类型简介以下介绍Hive的数据类型,Hive的数据类型分为四种类型,分别是:列类型文字Null值复杂类型列类型整型可以指定使用整型数据类型,下表描述了各种INT数据类型。(TINYINT<SMALLINT<INT<BIGINT)类型(后缀)示例TINYINT(Y)10YSMALLINT(S)1

  • cms垃圾收集器采用的回收算法_垃圾回收处理厂

    cms垃圾收集器采用的回收算法_垃圾回收处理厂CMSconcurrentmarkssweep并行标记清除垃圾回收机制。此篇文章是根据众多网上资料总结的关于CMS垃圾回收器的相关知识点。便于个人总结和回忆。垃圾回收器类型1、串行回收,Serial回收器,单线程回收,全程stw;2、并行回收,名称以Parallel开头的回收器,多线程回收,全程stw;3、并发回收,cms与G1,多线程分阶段回收,只有某阶段会stw;CMS垃圾回…

    2022年10月13日
  • python官方库和第三方库_python 第三方库

    python官方库和第三方库_python 第三方库转载地址:http://www.cnblogs.com/YangtzeYu/p/7858182.html

    2022年10月14日
  • 牛站_牛客网站

    牛站_牛客网站链接https://www.acwing.com/problem/content/submission/code_detail/1207146/题目给定一张由T条边构成的无向图,点的编号为1~1

  • GPS 数据格式

    GPS 数据格式GPS数据格式GPRMC(建议使用最小GPS数据格式)$GPRMC,,,,,,,,,,,1)标准定位时间(UTCtime)格式:时时分分秒秒.秒秒秒(hhmmss.sss)。2)定位状态,A=数据可用,V=数据不可用。3)纬度,格式:度度分分.分分分分(ddmm.mmmm)。4)纬度区分,北半球(N)或南半球(S)。5)经度,格式:度度分分.分分分分

  • impala读不到hive导入的数据(或者表找不到)

    impala读不到hive导入的数据(或者表找不到)

发表回复

您的电子邮箱地址不会被公开。

关注全栈程序员社区公众号