ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Noetic python raw Image publisher (from video)

asked 2021-12-14 23:53:54 -0500

USAotearoa gravatar image

Hi everyone, I have spent nearly 2 full days with this problem now and have some extensive research, but just can't figure it out. My apologies for being a burden, I ussually hesitate to waste anyones time. Before asking any questions I give it a good amount of effort.

I'm attempting to read a video stream from a file with opencv and then just publish every single fram on a topic. should be of message type sensor_msgs/Image

Once I have this completed, I will write a subscriber on a remote host, but I have to get the publisher done first, which is where I'm struggling. I have tried the below program, which executes without errors, until I add go into rviz and add new item by topic. that's when the application crashes.

I'm not sure at this point if the publisher works and the problem is on rviz side, or if the publisher is not properly set-up.

PLEASE help !

ROS noetic on Ubuntu 20_04 (native, not in a VM)

#! /usr/bin/env python

import rospy
import cv2
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import sys

VERBOSE=True

bridge = CvBridge()


def main(args):
    rospy.init_node('video_stream', anonymous=True)

    image_publisher = rospy.Publisher("/output/image_raw/stream", Image, queue_size=10)
    video_capture = cv2.VideoCapture('../video/ros.mp4')
    width  = video_capture.get(3)  # float `width`
    height = video_capture.get(4)  # float `height`

    if VERBOSE:
        print("initiated node and publisher")

    while not rospy.is_shutdown():
        try:
            ret, frame = video_capture.read()
            #cv_image = bridge.imgmsg_to_cv2(frame, "bgr8")

            vmsg = Image
            vmsg.header = rospy.Time.now()
            vmsg.height = height
            vmsg.width = width
            vmsg.encoding = "rgb8"
            vmsg.is_bigendian = True
            vmsg.step = 3
            vmsg.data = frame


            # Publish new image
            image_publisher.publish(vmsg)

        except KeyboardInterrupt:
            break
            print("Shutting down")    

    # </while>
    cv2.destroyAllWindows()

    return 0


if __name__ == '__main__':
    try:
        main(sys.argv)
    except KeyboardInterrupt:
        print("Shutting down")

Here is the error output I get when connecting it in rviz:

publish_video.py 
initiated node and publisher
Traceback (most recent call last):
  File "./publish_video.py", line 58, in <module>
    main(sys.argv)
  File "./publish_video.py", line 44, in main
    image_publisher.publish(vmsg)
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/topics.py", line 882, in publish
    self.impl.publish(data)
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/topics.py", line 1066, in publish
    serialize_message(b, self.seq, message)
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/msg.py", line 152, in serialize_message
    msg.serialize(b)
TypeError: serialize() missing 1 required positional argument: 'buff'
edit retag flag offensive close merge delete

Comments

Can you first listen to a topic in a terminal first to see if the first few Image messages are structured correctly? Shouldn't the line with vmsg = Image have a () on the end (for calling the constructor)?

ljaniec gravatar image ljaniec  ( 2021-12-15 01:34:59 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
4

answered 2021-12-15 01:42:01 -0500

USAotearoa gravatar image

Figured it out

#!/usr/bin/env python3

import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2

def publish_message():

  # Node is publishing to the video_frames topic using 
  # the message type Image
  pub = rospy.Publisher('video_frames', Image, queue_size=10)

  # Tells rospy the name of the node.
  # Anonymous = True makes sure the node has a unique name. Random
  # numbers are added to the end of the name.
  rospy.init_node('video_pub_py', anonymous=True)

  # Go through the loop 10 times per second
  rate = rospy.Rate(10) # 10hz

  # Create a VideoCapture object
  # The argument '0' gets the default webcam.
  #cap = cv2.VideoCapture(0)
  cap = cv2.VideoCapture('../video/ros.mp4')

  # Used to convert between ROS and OpenCV images
  br = CvBridge()

  # While ROS is still running.
  while not rospy.is_shutdown():

      # Capture frame-by-frame
      # This method returns True/False as well
      # as the video frame.
      ret, frame = cap.read()

      if ret == True:
        # Print debugging information to the terminal
        rospy.loginfo('publishing video frame')

        # Publish the image.
        # The 'cv2_to_imgmsg' method converts an OpenCV
        # image to a ROS image message
        pub.publish(br.cv2_to_imgmsg(frame))

      # Sleep just enough to maintain the desired rate
      rate.sleep()

if __name__ == '__main__':
  try:
    publish_message()
  except rospy.ROSInterruptException:
    pass
edit flag offensive delete link more

Comments

Thank you for your efforts and posting the answers so others can benefit.

osilva gravatar image osilva  ( 2021-12-15 07:28:47 -0500 )edit

Also you can accept your answer by clicking on the check mark.

osilva gravatar image osilva  ( 2021-12-15 07:29:29 -0500 )edit

Had to sign up to comment! This was useful in solving my problem. Thank you.

fegaeze gravatar image fegaeze  ( 2022-07-25 04:53:31 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-12-14 23:53:54 -0500

Seen: 979 times

Last updated: Dec 15 '21