00001 #include <ros/ros.h>
00002
00003 #include <iostream>
00004 #include <pcl_ros/point_cloud.h>
00005 #include <pcl/point_types.h>
00006 #include "pcl/io/pcd_io.h"
00007
00008 #include <pcl/kdtree/kdtree_flann.h>
00009 #include <pcl/surface/mls.h>
00010
00011 typedef pcl::PointXYZRGB PointType;
00012 typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
00013
00014 ros::Publisher pub_cloud;
00015
00016 PointCloud::Ptr temp(new PointCloud);
00017
00018
00019
00020
00021
00022 void callback(const PointCloud::ConstPtr& msg)
00023 {
00024 ROS_INFO("Beginning Moving Least Squares on %i Points", msg->points.size());
00025
00026
00027 pcl::copyPointCloud(*msg, *temp);
00028
00029
00030 pcl::KdTree<PointType>::Ptr tree (new pcl::KdTreeFLANN<PointType>);
00031 tree->setInputCloud (temp);
00032
00033
00034 PointCloud mls_points;
00035
00036
00037 pcl::MovingLeastSquares<PointType, pcl::Normal> mls;
00038
00039
00040 pcl::PointCloud<pcl::Normal>::Ptr mls_normals (new pcl::PointCloud<pcl::Normal> ());
00041 mls.setOutputNormals (mls_normals);
00042
00043
00044 mls.setInputCloud (temp);
00045 mls.setPolynomialFit (true);
00046 mls.setSearchMethod (tree);
00047 mls.setSearchRadius (0.05);
00048
00049
00050 mls.reconstruct(mls_points);
00051
00052 ROS_INFO("Done MLS");
00053
00054 pub_cloud.publish(mls_points);
00055 }
00056
00057
00058 int main(int argc, char** argv)
00059 {
00060 ros::init (argc, argv, "smooth_default");
00061
00062
00063 ros::NodeHandle nh = ros::NodeHandle(ros::this_node::getName());
00064 std::string cloud_in, cloud_out;
00065 nh.param<std::string>("cloud_in", cloud_in, "smooth_cloud_in");
00066 nh.param<std::string>("cloud_out", cloud_out, "smooth_cloud_out");
00067
00068
00069 ros::NodeHandle nx;
00070
00071 ros::Subscriber cloud_sub = nx.subscribe(cloud_in, 1, callback);
00072 pub_cloud = nx.advertise<PointCloud> (cloud_out, 1);
00073
00074 ros::spin();
00075
00076 return (0);
00077 }
00078
00079
00080