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

Publish Image msg

asked 2014-12-11 01:47:00 -0500

Holzroller gravatar image

Hey all,

I'm working on a code which publishes images coming from a camera (atm a video is used for testing). To publish those Images I would like to use the sensor_msgs. In the following is the code I got so far:

#!/usr/bin/env python

import rospy
from sensor_msgs.msg import Image

import cv2
from cv_bridge import CvBridge, CvBridgeError

rospy.init_node('VideoPublisher', anonymous=True)

VideoRaw = rospy.Publisher('VideoRaw', Image, queue_size=10)
NeedleBorder = rospy.Publisher('NeedleBorder', Image, queue_size=10)

cam = cv2.VideoCapture('output.avi')

while cam.isOpened():
    meta, frame = cam.read()

    frame_gaus = cv2.GaussianBlur(frame, gaussian_blur_ksize, gaussian_blur_sigmaX)

    frame_gray = cv2.cvtColor(frame_gaus, cv2.COLOR_BGR2GRAY)

    frame_edges = cv2.Canny(frame_gray, threshold1, threshold2)

    # I want to publish the Canny Edge Image and the original Image
    msg_frame = CvBridge().cv2_to_imgmsg(frame)
    msg_frame_edges = CvBridge().cv2_to_imgmsg(frame_edges)

    VideoRaw.publish(msg_frame, "RGB8")
    NeedleBorder.publish(msg_frame_edges, "mono8")

    time.sleep(0.1)

So the original image and the image the OpenCV Canny Edge Detector produces should be published.

If I run this code I just get the following output in the console once!: ...252, 255, 255, 252, 255, 255, 252, 255, 255, 252, 255, 255, 252, 255, 255, 252, 255, 255, 252, 255], 'RGB8')

But there isn't even a print command in my code o.O ? So it seems the code prints the original image once in the console and the program closes. If I rostopic echo both topics (in my code named 'VideoRaw' and 'NeedleBorder') I get to see nothing.

I would appreciate any help! Thanks a lot in advance!

edit retag flag offensive close merge delete

Comments

If you don't especially need sensor_msgs, I would use image_transport instead to publish images, it works fine.

Cyril Jourdan gravatar image Cyril Jourdan  ( 2014-12-11 03:05:55 -0500 )edit

If I'm not mistaken, its doesn't support Python yet: Python Usage

image_transport does not yet support Python, though it is on the Roadmap. If you need to interface a Python node with some compressed image transport, try interposing a republish node.

Holzroller gravatar image Holzroller  ( 2014-12-11 03:15:11 -0500 )edit

Ok, my bad, I use it with C++ so I assumed it was implemented in python...

Cyril Jourdan gravatar image Cyril Jourdan  ( 2014-12-11 03:32:49 -0500 )edit

3 Answers

Sort by » oldest newest most voted
0

answered 2014-12-11 03:22:26 -0500

Holzroller gravatar image

updated 2014-12-11 03:27:54 -0500

Somehow I feel really stupid now. The exactly same code in another directory works totally fine... ?!?! So there seems nothing wrong with the code ¯_(ツ)_/¯

edit flag offensive delete link more
1

answered 2017-03-27 20:47:11 -0500

Guan Heng gravatar image

np_arr = np.fromstring(ros_data.data, np.uint8) np_img = np_arr.reshape((480, 640, 3)) imshow(np_img)

edit flag offensive delete link more
0

answered 2021-04-11 07:01:09 -0500

aswath gravatar image

I got the same error: it ran once and printed out the values and stopped. Solved it as described below:

Instead of:

VideoRaw.publish(msg_frame, "bgr8")

It is supposed to be like this:

msg_frame = CvBridge().cv2_to_imgmsg(frame, "bgr8")

VideoRaw.publish(msg_frame)

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2014-12-11 01:45:42 -0500

Seen: 12,755 times

Last updated: Apr 11 '21