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

one node subscribes two hokuyo laser python [solved]

asked 2013-11-09 16:24:33 -0500

trbf gravatar image

updated 2014-01-28 17:18:29 -0500

ngrennan gravatar image

Hi,

I am using two laser hokuyo, one on top of the other to make a 360 degrees scan. I am working in python and i am making a node that simply join the information that come from the different topics.

However i don't know how to make to callbacks in the same node.I simply want that each call back calls from one topic, so that i can read both ranges and join them.

Can you help me?

Edit:

The error is:

[ERROR] [WallTime: 1384088332.419696] bad callback: <function callback2="" at="" 0x29cbed8=""> Traceback (most recent call last): File "/opt/ros/groovy/lib/python2.7/dist-packages/rospy/topics.py", line 681, in _invoke_callback cb(msg) File "/home/tiago/catkin_ws/src/test_python/listener.py", line 32, in callback2 cerebro(); File "/home/tiago/catkin_ws/src/test_python/listener.py", line 38, in cerebro copy(); File "/home/tiago/catkin_ws/src/test_python/listener.py", line 68, in copy pub.publish(LaserScan(laser)) File "/opt/ros/groovy/lib/python2.7/dist-packages/sensor_msgs/msg/_LaserScan.py", line 80, in __init__ super(LaserScan, self).__init__(args, *kwds) File "/opt/ros/groovy/lib/python2.7/dist-packages/genpy/message.py", line 271, in __init__ raise TypeError("Invalid number of arguments, args should be %s"%str(self.__slots__)+" args are"+str(args)) TypeError: Invalid number of arguments, args should be ['header', 'angle_min', 'angle_max', 'angle_increment', 'time_increment', 'scan_time', 'range_min', 'range_max', 'ranges', 'intensities'] args are(header:

And here is my code:

#!/usr/bin/env python import rospy from sensor_msgs.msg import LaserScan from std_msgs.msg import String from std_msgs.msg import Header import genpy

valores=[]
valores2=[]
valores_total=[]
idx=0;
flag=0;


def callback(header):
    global valores
    global flag
    flag=flag+1;
    valores=header.ranges
    if flag==2:
    cerebro();

def callback2(header): 
    global valores2
    global flag
    flag=flag+1; 
    valores2=header.ranges
    if flag==2:
    cerebro();


def cerebro():
    global valores_total
    valores_total=valores+valores2
    copy();



def copy():


    laser = LaserScan();
    header = Header();
    global idx
    global flag
    #creating header
    header.seq = idx;
    ftime_now = rospy.get_time();
    header.stamp = genpy.rostime.Time(int(ftime_now) // 1, int((ftime_now % 1.0)*1000000000)); 
    header.frame_id = "laser";

    laser.header = header;
    laser.angle_min = -3.14159;
    laser.angle_max = 3.14159;
    laser.angle_increment= 0.00613592332229;
    laser.time_increment= 9.76562514552e-05;
    laser.scan_time= 0.10000000149;
    laser.range_min= 0.019999999553;
    laser.range_max= 5.59999990463;
    laser.ranges=valores_total;


    pub = rospy.Publisher('chatter', LaserScan)
    rospy.loginfo(laser)
    pub.publish(LaserScan(laser))

    flag=0;
    idx=idx+1;


def listener():
    rospy.init_node('listener', anonymous=True)
    rospy.Subscriber("/scan", LaserScan, callback)
    rospy.Subscriber("/scan_front", LaserScan, callback2)
    rospy.spin()




if __name__ == '__main__':
    listener()

Thank you

EDIT:

Ok guys i think that i have solved the problem:

Instead of this:

pub = rospy.Publisher('chatter', LaserScan)
    rospy.loginfo(laser)
    pub.publish(LaserScan(laser))

i made this:

pub = rospy.Publisher('chatter', LaserScan)

    pub.publish(laser)

don't ask me why, i am new in ROS so some times i do things by intuition.

Thank you for your time!

edit retag flag offensive close merge delete

Comments

Does your code not work? Seems correct to me.

BennyRe gravatar image BennyRe  ( 2013-11-09 23:10:10 -0500 )edit

I think that it is wrong because i made it by intuition. I am gonna put the error and the all code in the topic. Thank you

trbf gravatar image trbf  ( 2013-11-10 01:01:46 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2013-11-10 01:56:19 -0500

BennyRe gravatar image

The error message says you provide not the correct number of arguments.

Please try:

def callback(header, angle_min, angle_max, angle_increment, time_increment, scan_time, range_min, range_max, ranges, intensities):

Not really sure about this. But you could try.

edit flag offensive delete link more

Comments

I tried that but this error appear: TypeError: callback() takes exactly 10 arguments (1 given) [ERROR] [WallTime: 1384098176.620008] bad callback: <function callback2="" at="" 0x2572ed8=""> Traceback (most recent call last): File "/opt/ros/groovy/lib/python2.7/dist-packages/rospy/topics.py", line 681, in _invoke_callback cb(msg) TypeError: callback2() takes exactly 10 arguments (1 given)

trbf gravatar image trbf  ( 2013-11-10 03:46:08 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2013-11-09 16:24:33 -0500

Seen: 1,884 times

Last updated: Nov 10 '13