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

Subcribe to multiple topics with message_filters

asked 2015-04-05 10:09:09 -0500

mmodetb gravatar image

updated 2015-04-05 19:37:19 -0500

Hello. I want to define a subscriber that subscribes to two different topics and sends the messages on it to just one callback. I have seen that the best to do that is to use message_filters.

Doubts:

  1. Does it mean that unless both messages contains in the topics change their value at the same time they will not be send to the callback?

  2. If callback needs two inputs: callback(input1, input2), how do I know if the proper message is associate to the proper input?

  3. The error that I obtain with the code bellow is the following:

    [ERROR] [WallTime: 1428256539.740225] bad callback: <bound method="" subscriber.callback="" of="" <message_filters.subscriber="" instance="" at="" 0xb6e36ecc="">> Traceback (most recent call last): File "/home/Clanton/ros_catkin_ws/install_isolated/lib/python2.7/dist-packages/rospy/topics.py", line 682, in _invoke_callback cb(msg) File "/home/Clanton/ros_catkin_ws/install_isolated/lib/python2.7/dist-packages/message_filters/__init__.py", line 73, in callback self.signalMessage(msg) File "/home/Clanton/ros_catkin_ws/install_isolated/lib/python2.7/dist-packages/message_filters/__init__.py", line 55, in signalMessage cb(*(msg + args)) File "/home/Clanton/ros_catkin_ws/install_isolated/lib/python2.7/dist-packages/message_filters/__init__.py", line 134, in add my_queue[msg.header.stamp] = msg AttributeError: 'Bool' object has no attribute 'header'

The code:

import rospy #based package to create Publishers and subcriber                                                                                  
from std_msgs.msg import Bool                 
import message_filters
import socket    # used for TCP/IP communication                                                                                                
import struct    # used to change the message format                                                                                            

TCP_IP = '192.168.1.105' #Relay board IP Adress                                                                                                 
TCP_PORT = 2101 #Relay board LAN PORT number                                                                                                    
BUFFER_SIZE = 1024

s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
s.connect((TCP_IP, TCP_PORT))


def controlling(gen1, gen2):
   print gen1
   if gen1==True:
       MESSAGE = struct.pack("BBB", 254, 108, 1)
       s.send(MESSAGE)

def listener():

   rospu.init_node('listener', anonymus=True)

   gen1_sub=message_filters.Subscriber('gen1topic', Bool)
   gen2_sub=message_filters.Subscriber('gen2topic', Bool)

   ts=message_filters.TimeSynchronizer([gen1_sub, gen2_sub],10,1)
   ts.registerCallback(controlling)                                                                                                     

   rospy.spin()

if __name__ == '__main__':
           listener()

If you could help me figure out if the problem is in the concept and thats why I cant use message_filter for this purpose or if there is something wrong in my code...

Thanks in advance,

Mercedes.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-04-10 02:09:37 -0500

ahendrix gravatar image

The time synchronizer in the message filters requires that your messages have a header with a timestamp, so that it can synchronize them based on time.

Bool messages don't have a header, so you can't use them with the message filters.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2015-04-05 10:09:09 -0500

Seen: 1,385 times

Last updated: Apr 10 '15