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

Problem running pointcloud_to_laserscan launch file

asked 2012-06-26 05:44:59 -0600

alexsleat gravatar image

updated 2017-07-17 22:17:29 -0600

M@t gravatar image

I'm attempting to use the pointcloud_to_laserscan stack with data we have collected from a sonar scan which has been converted in to pointcloud2 data. I'm a little confused at how nodelet's and also pointcloud_to_laserscan's work. I found (and attempted to replicate for this application) the turtlebot launch files for use with Kinect ( https://kforge.ros.org/turtlebot/turt... ) however it's still a little unclear.

The below launch file runs without error, however no laserScan msg is output.

<launch>
    <!--    DISPLAY NAME    NODE NAME       RUN NAME        ARGUMENTS       -->
    <node name="Scanner"    pkg="sonar"     type="sonar"    />
    <node name="Injector"   pkg="sonarInjector"     type="sonarInjector"    />
    <node name="Pointcloud" pkg="sonarPointCloud"   type="sonarPointCloud"  />

    <!-- fake laser -->
    <node pkg="nodelet" type="nodelet" name="sonarToLaser" args="load pointcloud_to_laserscan/CloudToScan sonarPointCloud">
    <param name="output_frame_id" value="/base_sonar2"/>
    <remap from="cloud" to="sonarPC"/>
    <remap from="scan" to="sonarLaserz"/>
    </node>
</launch>

Any advice on which direction to go in next and what might be wrong.

Thanks

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
1

answered 2012-06-27 02:14:42 -0600

alexsleat gravatar image

I managed to get this working as a nodelet, by just adding a nodelet manager (as below).

I'm still working on getting the sonar data correctly in to it, if I'm successful I will make sure to submit the code.

<launch>

    <!--    DISPLAY NAME    NODE NAME   RUN NAME    ARGUMENTS   -->
    <!-- <node name="Scanner"   pkg="sonar" type="sonar"    /> -->
    <!-- <node name="Injector"  pkg="sonarInjector" type="sonarInjector"    /> -->
    <!-- <node name="Pointcloud"    pkg="sonarPointCloud"   type="sonarPointCloud"  /> -->

    <node pkg="nodelet" type="nodelet" name="sonarManager" output="screen" respawn="true" args="manager"/>

<!-- fake laser -->
    <node pkg="nodelet" type="nodelet" name="sonarToLaser" args="load pointcloud_to_laserscan/CloudToScan sonarManager">
        <param name="output_frame_id" value="/base_sonar"/>
        <remap from="cloud" to="sonarPC"/>
        <remap from="scan" to="sonarLaser"/>
    </node>

</launch>
edit flag offensive delete link more

Comments

Hi alex, my work is similar to yours, but I'm directly publishing pointcloud from sonar sensor using range finder, when I use your launch file at start the things work fine but as soon as I subscribe sonarLaser topic the process dies and previous subscription also terminates. Can you guide me please

A_Saeed gravatar image A_Saeed  ( 2017-05-07 00:41:16 -0600 )edit

FYI, I found that this code didn't work for me as-is. I got a bunch of errors about "CloudToScan" not being a nodelet package.

M@t gravatar image M@t  ( 2017-07-17 22:23:03 -0600 )edit
3

answered 2012-06-26 15:52:11 -0600

weiin gravatar image

Have you tried running pointcloud_to_laserscan as a node?

From what I understand, nodelets require a nodelet manager to run. The turtlebot uses the openni_manager. Nodelets are used to process the same pointcloud through different algorithms (throttling, fake laser, narrow laser).

In your case, since you just need the fake laserscan, you probably can just run the pointcloud_to_laserscan as a node.

edit flag offensive delete link more

Comments

I have attempted to run as a node, however also having some problems with that. I replaced lines 32-37 with 39 as here (https://gist.github.com/3003036) however this returns an "undefined reference to `main'". I'm assuming this will require more code modification?

Also, thanks for the help!

alexsleat gravatar image alexsleat  ( 2012-06-26 23:53:02 -0600 )edit
0

answered 2017-07-17 22:50:37 -0600

M@t gravatar image

updated 2017-07-18 16:17:49 -0600

I've also encountered this problem when trying to run the pointcloud_to_laserscan launch files. I've got working launch files for an ordinary ROS node and a ROS nodelet (below), both of which are based on the sample launch files provided in the source code.

However, these sample files assume that you are deriving your point cloud from a RGBD camera, which is why the sample files launch an OpenNI2 node first. In my application I wanted to use pointcloud_to_laserscan on PointCloud2 data from a 3D LiDAR unit, and cut out all the OpenNI2 stuff.

pointcloud_to_lasercan node

The code I used for an ordinary pointcloud_to_laserscan node is:

<launch>
    <!-- run pointcloud_to_laserscan node -->
    <node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="pointcloud_to_laserscan">

        <remap from="cloud_in" to="<YOUR INPUT POINTCLOUD2 TOPIC>"/>
        <rosparam>
            target_frame: <THE FRAME OF YOUR POINTCLOUD2 TOPIC> 
            transform_tolerance: 0.01
            min_height: 0.0
            max_height: 1.0

            angle_min: -3.14 # -M_PI
            angle_max: 3.14 # M_PI
            angle_increment: 0.0087 # M_PI/360.0
            scan_time: 0.3333
            range_min: 0.45
            range_max: 10.0
            use_inf: true

            # Concurrency level, affects number of pointclouds queued for processing and number of threads used
            # 0 : Detect number of cores
            # 1 : Single threaded
            # 2->inf : Parallelism level
            concurrency_level: 0
        </rosparam>
    </node>
</launch>

This will launch a pointcloud_to_laserscan node that will immediately start converting and outputting data on the /scan topic. Note that if you delete the target_frame line or leave that parameter blank, you may get errors like I did. I found it best to explicitly keep the target_frame the same as the frame of the input PointCloud2 data. You can of course set the target frame to another frame entirely.

pointcloud_to_laserscan nodelet

Nodelets (as per gvdhoon's comments) are more efficient than regular nodes and offer reduced CPU usage, latency and jitter. In addition, the nodelet will not publish anything to the /scan topic unless it detects something subscribing to the topic, such as Rviz or "rostopic echo /scan".

The code I used to launch a pointcloud_to_laserscan nodelet is:

<launch>

    <!-- Create a manager becuase nodelets wont launch without one-->
    <node pkg="nodelet" type="nodelet" name="pointcloud_to_laserscan_manager" output="screen" respawn="true" args="manager"/>

    <!-- push pointcloud_to_laserscan nodelet into the dummny manager above-->
    <node pkg="nodelet" type="nodelet" name="pointcloud_to_laserscan_worker" args="load pointcloud_to_laserscan/pointcloud_to_laserscan_nodelet pointcloud_to_laserscan_manager">

        <remap from="cloud_in" to="<YOUR INPUT POINTCLOUD2 TOPIC>"/>
        <rosparam>
            target_frame: <THE FRAME OF YOUR POINTCLOUD2 TOPIC> 
            transform_tolerance: 0.01
            min_height: 0.0
            max_height: 1.0

            angle_min: -3.14 # -M_PI
            angle_max: 3.14 # M_PI
            angle_increment: 0.0087 # M_PI/360.0
            scan_time: 0.3333
            range_min: 0.45
            range_max: 10.0
            use_inf: true

            # Concurrency level, affects number of pointclouds queued for processing, thread number governed by nodelet manager
            # 0 : Detect number of cores
            # 1 : Single threaded
            # 2->inf : Parallelism level
            concurrency_level: 0
        </rosparam>
   </node>
</launch>

These launch files work for me, so hopefully they'll help anyone else with this problem.

edit flag offensive delete link more

Comments

The only practical benefit of a nodelet over a node (from my experience) [..]

the idea is that nodelets can skip the (de)serialisation step that is normally done when sending & receiving ROS msgs. If your driver supports it, that can avoid (de)serialisation of MB/s of traffic, reducing ..

gvdhoorn gravatar image gvdhoorn  ( 2017-07-18 01:52:18 -0600 )edit

.. CPU usage, latency and jitter.

gvdhoorn gravatar image gvdhoorn  ( 2017-07-18 01:52:38 -0600 )edit

I didn't realize nodelets did so much under the hood, thanks for pulling me up on this gvdhoon! I've updated the answer appropriately.

M@t gravatar image M@t  ( 2017-07-18 15:43:33 -0600 )edit

instead of using a standalone manager, should the nodelet manager created by realsense (realsense2_camera_manager) be used instead?

asraf gravatar image asraf  ( 2021-02-17 21:35:10 -0600 )edit

Question Tools

Stats

Asked: 2012-06-26 05:44:59 -0600

Seen: 3,129 times

Last updated: Jul 18 '17