-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathpassthrough.cpp
More file actions
35 lines (30 loc) · 962 Bytes
/
passthrough.cpp
File metadata and controls
35 lines (30 loc) · 962 Bytes
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/passthrough.h>
ros::Publisher pub;
void cb(const sensor_msgs::PointCloud2ConstPtr& ros_cloud)
{
pcl::PCLPointCloud2* p= new pcl::PCLPointCloud2;
pcl::PCLPointCloud2ConstPtr pPtr(p);
pcl_conversions::toPCL(*ros_cloud, *p);
pcl::PCLPointCloud2 p_filtered;
pcl::PassThrough<pcl::PCLPointCloud2> pass;
pass.setInputCloud(pPtr);
pass.setFilterFieldName ("z");
pass.setFilterLimits (1.3, 2.0);
pass.filter (p_filtered);
sensor_msgs::PointCloud2 output;
pcl_conversions::fromPCL(p_filtered, output);
pub.publish(output);
}
int main (int argc, char** argv)
{
ros::init (argc, argv, "passthrough");
ros::NodeHandle n;
ros::Subscriber s = n.subscribe ("/camera/depth/points", 1, cb);
pub = n.advertise<sensor_msgs::PointCloud2> ("output", 1);
ros::spin();
}