00001 /* 00002 * Copyright (C) 2016, DFKI GmbH 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of DFKI GmbH nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 * Authors: 00030 * Martin Günther <martin.guenther@dfki.de> 00031 * Jochen Sprickerhof <ros@jochen.sprickerhof.de> 00032 * 00033 */ 00034 00035 #include <ros/ros.h> 00036 00037 #include <pcl_conversions/pcl_conversions.h> 00038 00039 #include <sensor_msgs/PointCloud2.h> 00040 #include <sick_ldmrs_msgs/sick_ldmrs_point_type.h> 00041 #include <pcl_ros/point_cloud.h> 00042 00043 typedef sick_ldmrs_msgs::SICK_LDMRS_Point PointT; 00044 typedef pcl::PointCloud<PointT> PointCloudT; 00045 00046 ros::Publisher pub; 00047 00048 void callback(const PointCloudT::ConstPtr& cloud) 00049 { 00050 PointCloudT::Ptr cloud_filtered = boost::make_shared<PointCloudT>(); 00051 cloud_filtered->header = cloud->header; 00052 00053 // first: only publish first echo 00054 for (size_t i = 0; i < cloud->size(); i++) 00055 { 00056 if (cloud->points[i].echo == 0) 00057 { 00058 cloud_filtered->points.push_back(cloud->points[i]); 00059 } 00060 } 00061 00062 pub.publish(cloud_filtered); 00063 } 00064 00065 int main(int argc, char **argv) 00066 { 00067 ros::init(argc, argv, "sick_ldmrs_filter_first"); 00068 ros::NodeHandle nh; 00069 00070 ros::Subscriber sub = nh.subscribe("cloud", 1, callback); 00071 pub = nh.advertise<PointCloudT>("first", 1); 00072 00073 ros::spin(); 00074 00075 return 0; 00076 }