Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <pcl_ros/point_cloud.h>
00003 #include <pcl/point_types.h>
00004
00005 #include <iostream>
00006 #include "pcl/io/pcd_io.h"
00007
00008 #include "ClearpathPointCloudTools.h"
00009
00010 typedef pcl::PointXYZRGB PointType;
00011 typedef pcl::PointCloud<PointType> PointCloud;
00012
00013 ros::Publisher pub;
00014
00015 double dist = 0.0;
00016
00017 void callback(const PointCloud::ConstPtr& cloud)
00018 {
00019 PointCloud result;
00020 ClearpathPointCloudTools::PassthroughPointCloud((PointCloud*)&(*cloud), &result, dist);
00021 pub.publish (result);
00022 }
00023
00024 int main(int argc, char** argv)
00025 {
00026 ros::init (argc, argv, "passthrough_default");
00027
00028 ros::NodeHandle nh = ros::NodeHandle(ros::this_node::getName());
00029 std::string in, out;
00030 nh.param<std::string>("in", in, "passthrough_in");
00031 nh.param<std::string>("out", out, "passthrough_out");
00032 nh.param<double>("dist", dist, 1.0);
00033
00034 ros::NodeHandle nx;
00035 ros::Subscriber sub = nx.subscribe<PointCloud>(in, 1, callback);
00036 pub = nx.advertise<PointCloud> (out, 1);
00037
00038 ros::spin();
00039
00040 return (0);
00041 }
00042
00043
00044