## repository: https://code.ros.org/svn/ros-pkg <> <> == Overview == This package provides interfaces and tools for bridging a running ROS system to the Point Cloud Library. These include ROS nodelets, nodes, and C++ interfaces. == ROS nodelets == `pcl_ros` includes several [[http://www.ros.org/wiki/pcl_ros/Filters|PCL filters]] packaged as ROS nodelets. These links provide details for using those interfaces: * [[http://www.ros.org/wiki/pcl_ros/Tutorials/filters#Extract_Indices|Extract_Indices]] * [[http://www.ros.org/wiki/pcl_ros/Tutorials/filters#PassThrough|PassThrough]] * [[http://www.ros.org/wiki/pcl_ros/Tutorials/filters#ProjectInliers|ProjectInliers]] * [[http://www.ros.org/wiki/pcl_ros/Tutorials/filters#RadiusOutlierRemoval|RadiusOutlierRemoval]] * [[http://www.ros.org/wiki/pcl_ros/Tutorials/filters#StatisticalOutlierRemoval|StatisticalOutlierRemoval]] * [[http://www.ros.org/wiki/pcl_ros/Tutorials/filters#VoxelGrid|VoxelGrid]] == ROS C++ interface == `pcl_ros` extends the ROS [[roscpp|C++ client library]] to support message passing with [[pcl|PCL]] native data types. Simply add the following include to your ROS node source code: {{{ #include }}} This header allows you to publish and subscribe [[http://www.ros.org/doc/api/pcl/html/classpcl_1_1PointCloud.html|pcl::PointCloud]] objects as ROS messages. These appear to ROS as <> messages, offering seamless interoperability with non-PCL-using ROS nodes. For example, you may publish a `pcl::PointCloud` in one of your nodes and visualize it in [[rviz]] using a [[rviz/DisplayTypes/PointCloud|Point Cloud2 display]]. It works by hooking into the [[roscpp/Overview/MessagesSerializationAndAdaptingTypes|roscpp serialization]] infrastructure. The old format <> is not supported in PCL. === Publishing point clouds === You may publish PCL point clouds using the standard `ros::Publisher`: {{{#!cplusplus #include #include #include #include typedef pcl::PointCloud PointCloud; int main(int argc, char** argv) { ros::init (argc, argv, "pub_pcl"); ros::NodeHandle nh; ros::Publisher pub = nh.advertise ("points2", 1); PointCloud::Ptr msg (new PointCloud); msg->header.frame_id = "some_tf_frame"; msg->height = msg->width = 1; msg->points.push_back (pcl::PointXYZ(1.0, 2.0, 3.0)); ros::Rate loop_rate(4); while (nh.ok()) { pcl_conversions::toPCL(ros::Time::now(), msg->header.stamp); pub.publish (*msg); ros::spinOnce (); loop_rate.sleep (); } } }}} === Subscribing to point clouds === You may likewise subscribe to PCL point clouds using the standard `ros::Subscriber`: {{{#!cplusplus #include #include #include #include typedef pcl::PointCloud PointCloud; void callback(const PointCloud::ConstPtr& msg) { printf ("Cloud: width = %d, height = %d\n", msg->width, msg->height); BOOST_FOREACH (const pcl::PointXYZ& pt, msg->points) printf ("\t(%f, %f, %f)\n", pt.x, pt.y, pt.z); } int main(int argc, char** argv) { ros::init(argc, argv, "sub_pcl"); ros::NodeHandle nh; ros::Subscriber sub = nh.subscribe("points2", 1, callback); ros::spin(); } }}} == ROS nodes == Several tools run as ROS nodes. They convert ROS messages or bags to and from Point Cloud Data (PCD) file format. <> {{{ #!clearsilver CS/NodeAPI node.0 { name=bag_to_pcd desc=Reads a bag file, saving all ROS point cloud messages on a specified topic as PCD files. } }}} ==== Usage ==== {{{ $ rosrun pcl_ros bag_to_pcd }}} Where: * is the bag file name to read. * is the topic in the bag file containing messages to save. * is the directory on disk in which to create PCD files from the point cloud messages. ==== Example ==== Read messages from the `/laser_tilt_cloud` topic in `data.bag`, saving a PCD file for each message into the `./pointclouds` subdirectory. {{{ $ rosrun pcl_ros bag_to_pcd data.bag /laser_tilt_cloud ./pointclouds }}} <> {{{ #!clearsilver CS/NodeAPI node.0 { name=convert_pcd_to_image desc=Loads a PCD file, publishing it as a ROS image message five times a second. pub { 0.name=output 0.type=sensor_msgs/Image 0.desc=A stream of images generated from the PCD file. } } }}} ==== Usage ==== {{{ $ rosrun pcl_ros convert_pcd_to_image }}} Read the point cloud in and publish it in ROS image messages at 5Hz. <> {{{ #!clearsilver CS/NodeAPI node.0 { name=convert_pointcloud_to_image desc=Subscribes to a ROS point cloud topic and republishes image messages. sub { 0.name=input 0.type=sensor_msgs/PointCloud2 0.desc=A stream of point clouds to convert to images. } pub { 0.name=output 0.type=sensor_msgs/Image 0.desc=Corresponding stream of images. } } }}} ==== Examples ==== Subscribe to the `/my_cloud` topic and republish each message on the `/my_image` topic. {{{ $ rosrun pcl_ros convert_pointcloud_to_image input:=/my_cloud output:=/my_image }}} To view the images created by the previous command, use [[image_view]]. {{{ $ rosrun image_view image_view image:=/my_image }}} <> {{{ #!clearsilver CS/NodeAPI node.0 { name=pcd_to_pointcloud desc=Loads a PCD file, publishing it one or more times as a ROS point cloud message. pub { 0.name=cloud_pcd 0.type=sensor_msgs/PointCloud2 0.desc=A stream of point clouds generated from the PCD file. } param { 0.name=~frame_id 0.type=str 0.default=/base_link 0.desc=Transform frame ID for published data. } } }}} ==== Usage ==== {{{ $ rosrun pcl_ros pcd_to_pointcloud [ ] }}} Where: * is the (required) file name to read. * is the (optional) number of seconds to sleep between messages. If is zero or not specified the message is published once. ==== Examples ==== Publish the contents of `point_cloud_file.pcd` once in the `/base_link` frame of reference. {{{ $ rosrun pcl_ros pcd_to_pointcloud point_cloud_file.pcd }}} Publish the contents of `cloud_file.pcd` approximately ten times a second in the `/odom` frame of reference. {{{ $ rosrun pcl_ros pcd_to_pointcloud cloud_file.pcd 0.1 _frame_id:=/odom }}} <> {{{ #!clearsilver CS/NodeAPI node.0 { name=pointcloud_to_pcd desc=Subscribes to a ROS topic and saves point cloud messages to PCD files. Each message is saved to a separate file, names are composed of an optional `prefix` parameter, the ROS time of the message, and the `.pcd` extension. sub { 0.name=input 0.type=sensor_msgs/PointCloud2 0.desc=A stream of point clouds to save as PCD files. } param { 0.name=~prefix 0.type=str 0.desc=Prefix for PCD file names created. 1.name=~fixed_frame 1.type=str 1.desc=If set, the transform from the fixed frame to the frame of the point cloud is written to the VIEWPOINT entry of the pcd file. 2.name=~binary 2.type=bool 2.default=false 2.desc=Output the pcd file in binary form. 3.name=~compressed 3.type=bool 3.default=false 3.desc=In case that binary output format is set, use binary compressed output. } } }}} ==== Examples ==== Subscribe to the `/velodyne/pointcloud2` topic and save each message in the current directory. File names look like `1285627014.833100319.pcd`, the exact names depending on the message time stamps. {{{ $ rosrun pcl_ros pointcloud_to_pcd input:=/velodyne/pointcloud2 }}} Set the `prefix` parameter in the current namespace, save messages to files with names like `/tmp/pcd/vel_1285627015.132700443.pcd`. {{{ $ rosrun pcl_ros pointcloud_to_pcd input:=/my_cloud _prefix:=/tmp/pcd/vel_ }}} == More examples == We have more examples on http://wiki.ros.org/pcl_ros/Tutorials page ## AUTOGENERATED DON'T DELETE ## CategoryPackage