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

Laser_assemble for Hokuyo scans in Gazebo

asked 2017-08-04 13:19:15 -0500

Burgos gravatar image

Hi everyone!

I'm trying to assemble some readings from a Hokuyo laser simulated in gazebo.

The assembler I'm trying to use is the one you can download here: https://github.com/ros-perception/las...

Once I have downloaded and catkin_maked it, I run the gazebo simulation, which publish the topic /mybot/laser/scan with the planar scan. I can perfectly visualize that scan in rviz by setting the fixed frame to a topic called "odom" and adding a LaserScan with the /mybot/laser/scan topic.

Then, I create the following launch file called "hokuyo_assembler.launch":

<launch>
  <node pkg="laser_assembler" type="laser_scan_assembler" output="screen"  name="laser_scan_assembler">
    <remap from="/mybot/laser/scan" to="assebled_scan"/>
    <param name="tf_cache_time_secs" type="double" value="10.0" />
    <param name="max_scans" type="int" value="400" />
    <param name="ignore_laser_skew" type="bool" value="true" />
    <param name="fixed_frame" type="string" value="odom" />
  </node>
</launch>

but when I try in a new terminal "roslaunch laser_assembler hokuyo_assembler.launch", it does not publish any new topic, it only says the following:

SUMMARY

PARAMETERS
 * /laser_scan_assembler/fixed_frame: odom
 * /laser_scan_assembler/ignore_laser_skew: True
 * /laser_scan_assembler/max_scans: 400
 * /laser_scan_assembler/tf_cache_time_secs: 10.0
 * /rosdistro: kinetic
 * /rosversion: 1.12.7

NODES
  /
    laser_scan_assembler (laser_assembler/laser_scan_assembler)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[laser_scan_assembler-1]: started with pid [13103]
[ INFO] [1501870597.118463994]: TF Cache Time: 10.000000 Seconds
[ INFO] [1501870597.122609645]: Max Scans in History: 400
[ INFO] [1501870597.128738188]: Fixed Frame: odom

Any idea of how can I create the topic with the assembled scans?

Thanks in advance.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2017-10-23 07:26:21 -0500

Alberto E. gravatar image

updated 2017-10-23 07:29:16 -0500

Hello,

As @tfoote says, the first thing you need to do is remap the scan topic to the one where the laser data is being published in your case. Here you have an example launch file (where the Hokuyo data is published into the /kobuki/laser/scan topic):

<launch>
  <node pkg="laser_assembler" type="laser_scan_assembler" output="screen"  name="laser_scan_assembler">
    <remap from="scan" to="/kobuki/laserscan"/>
    <param name="tf_cache_time_secs" type="double" value="10.0" />
    <param name="max_scans" type="int" value="400" />
    <param name="ignore_laser_skew" type="bool" value="true" />
    <param name="fixed_frame" type="string" value="base_link" />
  </node>
</launch>

Also, the output provided by the laser_scan_assembler node is given through services, so you will need to perform a call to that service in order to get the Pointcloud data associated to your laser readings. Here you have an example code that does that:

#!/usr/bin/env python

import rospy 
from laser_assembler.srv import *
from sensor_msgs.msg import PointCloud2

rospy.init_node("client_test")
rospy.wait_for_service("assemble_scans2")
assemble_scans = rospy.ServiceProxy('assemble_scans2', AssembleScans2)
pub = rospy.Publisher ("/pointcloud", PointCloud2, queue_size=1)
r = rospy.Rate (1)

while not rospy.is_shutdown():
    try:
        resp = assemble_scans(rospy.Time(0,0), rospy.get_rostime())
        print "Got cloud with %u points" % len(resp.cloud.data)
        pub.publish (resp.cloud)

    except rospy.ServiceException, e:
        print "Service call failed: %s"%e

    r.sleep()

So basically, what this code does is to perform calls to the /assemble_scan2 service, which provides the PointCloud2 data, and then publish this data into a topic, so you can, for instance, visualize it in RViz.

I have also created this video whith the whole process which I think it may help you understand it better.

edit flag offensive delete link more
0

answered 2017-10-16 17:35:31 -0500

tfoote gravatar image

You need to remap you scan to the input topic. And the output is provided on a service not a topic. Please see the API documentation here: http://wiki.ros.org/laser_assembler

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2017-08-04 13:19:15 -0500

Seen: 1,023 times

Last updated: Oct 23 '17