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

Some questions about velodyne_pointcloud package

asked 2014-08-03 03:10:42 -0600

Lau gravatar image

updated 2014-08-03 04:04:47 -0600

Hello! I am learning ROS recently . I have some questions about velodyne package:

  1. After I run "$roslaunch velodyne_pointcloud 32e_points.launch calibration:=/home/llm/catkin_ws/src/velodyne_pointcloud/params/32db.yaml" in the terminal , which .cpp file in src/conversions/ was executed ?

  2. I notice that in the file convert.cpp , "output_" publish a "outMsg" (velodyne_rawdata::VPointtCloud::Ptr) in line 78,but in line 31 ,the "output_" advertise "sensor_msgs::PointCloud2" message ,I can not understand this code.

  3. I am focused on this one . I created a node to subscribe the topic "velodyne_points" , and I want to extract the information of the points's XYZ coordinate value from the topic , but I can not understand the message type "sensor::PointCloud2", what should I do?

Looking for you reply ! Thank you very much !

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2014-08-03 09:34:01 -0600

joq gravatar image

updated 2014-08-04 09:17:24 -0600

  1. That launch file runs the cloud nodelet in a velodyne_nodelet manager process. The cloud nodelet is built using cloud_nodelet.cc and convert.cc.

  2. The constructor must advertise the topic before the callback can publish to it.

  3. An example of reading the individual points in the message is here in RingColors::convertPoints, a method that reads /velodyne_points and publishes a colored cloud containing the same points in /velodyne_rings.

EDIT: To run the Ring Colors nodelet, you can create your own launch file, something like this (untested):

<include file="$(find velodyne_pointcloud)/launch/32e_points.launch" />
<node pkg="nodelet" type="nodelet" name="ring_colors_nodelet"
      args="load velodyne_pointcloud/RingColorsNodelet velodyne_nodelet_manager" />
edit flag offensive delete link more

Comments

Thank you . 1. For the second question , I mean that the "outMsg" is not a type "sensor_msgs::PointCloud2" message . In my previous study , I noticed that the types should be same like the code(copied from the tutorials) listed : { ros::Publisher chatter_pub = n.advertise<std_msgs::string>("chatter", 1000); ... std_msgs::String msg; ... chatter_pub.publish(msg); } 2. For the third question. If I want to run the ringcolors_nodelet.cc and colors.cc and read the point's message , should I creat a .launch file like the cloud_nodelet.launch and add it to 32e_points.launch?

Lau gravatar image Lau  ( 2014-08-04 02:41:31 -0600 )edit

pcl_ros and pcl_conversions provide a callback interface for the PointCloud2 message, converting it to a PCL point cloud, which the code can conveniently manipulate.

joq gravatar image joq  ( 2014-08-04 09:08:26 -0600 )edit

Thank you ! now I can read the individual point now !

Lau gravatar image Lau  ( 2014-08-04 18:21:35 -0600 )edit

If this answers your question, please click the check mark.

joq gravatar image joq  ( 2014-08-05 08:35:21 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2014-08-03 03:10:42 -0600

Seen: 1,606 times

Last updated: Aug 04 '14