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

how to subscribe to laser /scan topic and publish a customized scan topic back

asked 2021-02-16 03:18:54 -0500

siddharthcb gravatar image

updated 2021-02-16 04:31:50 -0500

hi, i want to consider any 72 points from the 'scan' topic for my other application. Currently the lidar i am using gives around 2000 points. I want to take only 72 points out of it and publish it as a new topic 'revised_scan'. I tried with a small script in python:

#! /usr/bin/env python

import rospy
from sensor_msgs.msg import LaserScan
import sensor_msgs.msg

pub = rospy.Publisher('/revised_scan', LaserScan, queue_size = 10)

rev_scan = LaserScan()

def callback(msg):
    #print(len(msg.ranges)) len is 2019 from 0-360
    req_range = rev_scan.msg.ranges[0:72]
    pub.publish(req_range)

def listener():
    rospy.init_node('revised_scan', anonymous=True)
    sub = rospy.Subscriber('/scan', LaserScan, callback)
    rospy.spin()

if __name__ == '__main__':
    listener()

however, it gives me an error saying

[ERROR] [1613466169.831151]: bad callback: <function callback at 0x7f99a8d350>
Traceback (most recent call last):
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
    cb(msg)
  File "rev_scan.py", line 12, in callback
    req_range = rev_scan.msg.ranges[0:72]
AttributeError: 'LaserScan' object has no attribute 'msg'

Though i can change directly in the lidars source file to publish two topics(scan & revised_scan) but I want to make this as a standard irrespective of the type of lidar I will use in the future.

I appreciate if someone can help with this.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2021-02-16 04:56:15 -0500

siddharthcb gravatar image

updated 2021-02-16 04:56:41 -0500

I made changes to my code as roberto mentioned and works fine.

 #! /usr/bin/env python

import rospy
from sensor_msgs.msg import LaserScan
import sensor_msgs.msg

pub = rospy.Publisher('/revised_scan', LaserScan, queue_size = 10)
scann = LaserScan()

def callback(msg):
    #print(len(msg.ranges)) len is 2019 from 0-360
    current_time = rospy.Time.now()
    scann.header.stamp = current_time
    scann.header.frame_id = 'laser'
    scann.angle_min = -3.1415
    scann.angle_max = 3.1415
    scann.angle_increment = 0.00311202858575
    scann.time_increment = 4.99999987369e-05
    scann.range_min = 0.00999999977648
    scann.range_max = 32.0
    scann.ranges = msg.ranges[0:72]
    scann.intensities = msg.intensities[0:72]
    print(scann)
    pub.publish(scann)

def listener():
    rospy.init_node('revised_scan', anonymous=True)
    sub = rospy.Subscriber('/scan', LaserScan, callback)
    rospy.spin()

if __name__ == '__main__':
    listener()
edit flag offensive delete link more

Comments

I'm glad you got it working!

Roberto Z. gravatar image Roberto Z.  ( 2021-02-16 05:13:34 -0500 )edit
3

answered 2021-02-16 04:20:28 -0500

Roberto Z. gravatar image

updated 2021-02-16 04:28:58 -0500

Not a complete answer, as your code has several problems.

Here is one: When new messages are received, msg is the variable name for the message that is passed in.

So:

rev_scan.msg.ranges[0:72]

should be

msg.ranges[0:72]

Also, note that you have not initialized the message req_scan which you are publishing but you initialized rev_scan instead, and also you are assigning the ranges to a different variable namely req_range.

sensor_msgs/LaserScan Message is a somewhat complicated message type, I recommend that you start by trying to republish a simpler message type like std_msgs/String and then move on to more complicated types.

This is a good place to start:

http://wiki.ros.org/ROS/Tutorials/Wri...

edit flag offensive delete link more

Comments

oops! thanks. that was a blunder. i have enclosed my edited code in the next post.

siddharthcb gravatar image siddharthcb  ( 2021-02-16 04:52:12 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-02-16 03:18:54 -0500

Seen: 6,405 times

Last updated: Feb 16 '21