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

How to subcribe both Image topic and Text topic in the same time ?

asked 2019-01-30 20:56:54 -0500

ToanJunifer gravatar image

updated 2019-01-31 02:02:09 -0500

Hi buddy, I am newbie in ROS. And this is the first time i'm trying to subcribe 2 topics type, 1 for Image topic and 1 for Array of ints topic. And i have a problem on it. This is my source code:

#!/usr/bin/env python
import sys
import rospy
import cv2
import math
import message_filters
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
from std_msgs.msg import String,Int32,Int32MultiArray,MultiArrayLayout,MultiArrayDimension

class image_converter:
  def __init__(self):
    self.bridge = CvBridge()
    self.image_sub = message_filters.Subscriber("/laptop/camera",Image)
    self.array_sub = message_filters.Subscriber("Arduino_Publish", Int32MultiArray)
  def callback(image,data):
    cv_image = bridge.imgmsg_to_cv2(image, "bgr8")

    def draw(img):
       cv2.circle(cv_image,(100,100),50,(0,0,255),2)
       return img
    data_receive = value.data
    rospy.logwarn(value.data)
    frame = draw(cv_image)
    cv2.imshow("Frame", frame)
    cv2.waitKey(3)

def main():
  img_cvt = image_converter()
  rospy.init_node('Sub_2_Topic', anonymous=True)
  try:
    ts = message_filters.ApproximateTimeSynchronizer([img_cvt.image_sub,img_cvt.array_sub],10,0.1)
    ts.registerCallback(img_cvt.callback)
    rospy.spin()
  except KeyboardInterrupt:
    print("Shutting down")
if __name__ == '__main__':
    main()

And i sent Image message and Text message successfully and receive them individual. Then i try using message filter to receive both of them, and i got error:

[ERROR] [WallTime: 1548902849.013077] bad callback: <bound method Subscriber.callback of <message_filters.Subscriber object at 0x7fd39b1628d0>>
Traceback (most recent call last):
  File "/opt/ros/indigo/lib/python2.7/dist-packages/rospy/topics.py", line 720, in _invoke_callback
    cb(msg)
  File "/opt/ros/indigo/lib/python2.7/dist-packages/message_filters/__init__.py", line 74, in callback
    self.signalMessage(msg)
  File "/opt/ros/indigo/lib/python2.7/dist-packages/message_filters/__init__.py", line 56, in signalMessage
    cb(*(msg + args))
  File "/opt/ros/indigo/lib/python2.7/dist-packages/message_filters/__init__.py", line 221, in add
    my_queue[msg.header.stamp] = msg
AttributeError: 'Int32MultiArray' object has no attribute 'header'

So, what should i do to fix this, now ? Thank you !

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2019-01-31 00:51:20 -0500

mgruhler gravatar image

Int32MultiArray of pacakge std_msgs is a primitive data type and as such does not contain a header. This is what your error message is telling you.

Typcially, the timestamp in the headers are used to synchronize the messages.

There is a "workaround", however. To quote the wiki

If some messages are of a type that doesn't contain the header field, ApproximateTimeSynchronizer refuses by default adding such messages. However, its Python version can be constructed with allow_headerless=True, which uses current ROS time in place of any missing header.stamp field

See the relevant section of the message_filters ROS wiki.

(Nitpicking: Your question is asking about syncing image and text, but it is actually image and array of ints...)

edit flag offensive delete link more

Comments

I going to fix follow your guide. Thank you for your advise

ToanJunifer gravatar image ToanJunifer  ( 2019-01-31 01:36:24 -0500 )edit

I added:

ts = message_filters.ApproximateTimeSynchronizer([image_sub,array_sub],10,0.1,allow_headerless=True)

I get:

TypeError: __init__() got an unexpected keyword argument 'allow_headerless'
ToanJunifer gravatar image ToanJunifer  ( 2019-01-31 01:49:26 -0500 )edit
1

which ROS version? You selected indigo. If this is true, you might be out of luck. This seems to be only in kinetic onwards...

mgruhler gravatar image mgruhler  ( 2019-01-31 04:50:36 -0500 )edit

Oh god. May be i need another solution for my case. Thank you so much for your support. I very respect it.

ToanJunifer gravatar image ToanJunifer  ( 2019-01-31 20:49:14 -0500 )edit

I'd recommend updating to a newer version of Ubuntu/ROS. Indigo is still supported, but will be EOL'd in April. Check http://wiki.ros.org/Distributions for the supported ROS distros and how long they will be supported.

mgruhler gravatar image mgruhler  ( 2019-02-01 00:59:06 -0500 )edit

Thank you, @mgruhler. That would be helpful info

ToanJunifer gravatar image ToanJunifer  ( 2019-02-01 08:13:50 -0500 )edit
0

answered 2019-01-31 00:47:18 -0500

ahendrix gravatar image

You need to use stamped message types (messages with a header field) with the ApproximateTimeSynchronizer . You should change the Int32MultiArray message type to a stamped type.

This looks a lot like a homework question, so I'm not going to give you any more hints than that.

edit flag offensive delete link more

Comments

Thank you, buddy. And this isnt a homework question. I research about ROS for myself. So, we can discuss more about it :)

ToanJunifer gravatar image ToanJunifer  ( 2019-01-31 01:38:06 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-01-30 20:56:54 -0500

Seen: 1,103 times

Last updated: Jan 31 '19