sick_ldmrs_filter_layer.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016, DFKI GmbH
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of DFKI GmbH nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Authors:
30  * Martin Günther <martin.guenther@dfki.de>
31  * Jochen Sprickerhof <ros@jochen.sprickerhof.de>
32  *
33  */
34 
35 #include <ros/ros.h>
36 
38 
39 #include <sensor_msgs/PointCloud2.h>
41 #include <pcl_ros/point_cloud.h>
42 
44 typedef pcl::PointCloud<PointT> PointCloudT;
45 
47 
48 void callback(const PointCloudT::ConstPtr& cloud)
49 {
50  PointCloudT::Ptr cloud_filtered = boost::make_shared<PointCloudT>();
51  cloud_filtered->header = cloud->header;
52 
53  // layer1: only publish points from second layer
54  for (size_t i = 0; i < cloud->size(); i++)
55  {
56  if (cloud->points[i].layer == 1)
57  {
58  cloud_filtered->points.push_back(cloud->points[i]);
59  }
60  }
61 
62  pub.publish(cloud_filtered);
63 }
64 
65 int main(int argc, char **argv)
66 {
67  ros::init(argc, argv, "sick_ldmrs_filter_layer");
68  ros::NodeHandle nh;
69 
70  ros::Subscriber sub = nh.subscribe("cloud", 1, callback);
71  pub = nh.advertise<PointCloudT>("layer1", 1);
72 
73  ros::spin();
74 
75  return 0;
76 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
void callback(const PointCloudT::ConstPtr &cloud)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pub
pcl::PointCloud< PointT > PointCloudT
sick_ldmrs_msgs::SICK_LDMRS_Point PointT
pcl::PointCloud< PointT > PointCloudT


sick_ldmrs_tools
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Sun Oct 25 2020 03:33:58