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

extract SensorMessages/LaserScan from SensorMessages/PointCloud2 created in simulation

asked 2013-10-07 00:47:52 -0500

Yami gravatar image

Hello all,

This is my problem: v-rep publishes data from a simulated LMS100 in the form of SensorMessages/PointCloud2 on ROS, but i need SensorMessages/LaserScan. I have installed the pointcloud_to_laserscan package but it seems to be only for Kinect. I have no idea how to use it with pointcloud data already there(and not from Kinect).Can anyone help me with that please?

Thanks in advance.

edit retag flag offensive close merge delete

Comments

you may just need to adjust some parameters. The pointcloud_to_laserscan essentially just takes a horizontal slice from the point cloud and makes that the "laser scan". The points in the point cloud could be out of that height range.

jdorich gravatar image jdorich  ( 2013-10-07 13:45:23 -0500 )edit

Thanks jdorich, but the problem is i have no idea how to use this pointcloud_to_laserscan package. So I wrote my own node which subscribes for pointclouds in vrep, #include "ros/ros.h" #include "std_msgs/String.h" #include <sensor_msgs pointcloud2.h=""> #include <sensor_msgs laserscan.h=""> /** * subscribe pointcloud from v-rep */ void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr& Cloud) { ROS_INFO("Clouds Received"); } int main(int argc, char **argv) { ros::init(argc, argv, "cloudtoscan"); ros::NodeHandle n; ros::Subscriber cloud_sub = n.subscribe("/vrep/PointCloud2", 100, cloudCallback);

Yami gravatar image Yami  ( 2013-10-07 23:05:03 -0500 )edit

But from here i don't know how to write the program. I know how to change point data to angle data, but do not know how to do that in every single scan. Can u please help me with that?

Yami gravatar image Yami  ( 2013-10-07 23:09:06 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2013-10-08 13:04:11 -0500

jdorich gravatar image

updated 2013-10-10 02:57:46 -0500

I believe you can run the pointcloud_to_laserscan for any Sensor_msgs/PointCloud2 data by the following (in this case I've matched what you have put above for the vrep):

<launch>
  <!-- Fake Laser Standalone nodelet-->
  <node pkg="nodelet" type="nodelet" name="vrep_laser" args="standalone pointcloud_to_laserscan/CloudToScan" respawn="true">
    <param name="output_frame_id" value="/vrep_frame"/>
    <param name="min_height" value="-0.15"/>
    <param name="max_height" value="0.15"/>
    <remap from="cloud" to="/vrep/PointCloud2"/>
  </node> 

</launch>

Adjust the "output_frame_id", "min_height", and "max_height" as necessary for the vrep Sensor_msgs/PointCloud2 data.

This tutorial has information on nodelets and running standalone nodelets and this turtlebot file shows an example for how to run the pointcloud_to_laserscan nodelet. The code I have above follow these.

Hopefully this helps.

edit flag offensive delete link more

Comments

Thanks a lot jdorich . That is exactly what i looked for.

Yami gravatar image Yami  ( 2013-10-09 20:54:39 -0500 )edit

Great! See updated answer. I forgot that you could set standalone as an arg rather than loading a standalone nodelet manager.

jdorich gravatar image jdorich  ( 2013-10-10 02:58:37 -0500 )edit

thanks again

Yami gravatar image Yami  ( 2013-10-10 22:05:39 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2013-10-07 00:47:52 -0500

Seen: 683 times

Last updated: Oct 10 '13