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.